diff --git a/.gitignore b/.gitignore index 0f214e3..b27cf10 100644 --- a/.gitignore +++ b/.gitignore @@ -14,6 +14,7 @@ drivers/**/.tmp_versions/ user/**/*.o user/show_ip/show_ip user/streaming_sensors/streaming_sensors +user/infrared/infrared # ModelSim temporary files work/ @@ -23,6 +24,7 @@ transcript # Quartus temporary files .qsys_edit/ +subsystemHMI/ db/ HPSPlatform/ incremental_db/ diff --git a/drivers/infrared/Makefile b/drivers/infrared/Makefile new file mode 100644 index 0000000..86562b6 --- /dev/null +++ b/drivers/infrared/Makefile @@ -0,0 +1,23 @@ +modulename := infrared + +obj-m += $(modulename).o + + +all: + $(MAKE) -C $(KERNEL_SRC) M=$(PWD) + +modules_install: + $(MAKE) -C $(KERNEL_SRC) M=$(PWD) modules_install + +clean: + rm -f *.o *~ core .depend .*.cmd *.ko *.mod.c + rm -f Module.markers Module.symvers modules.order + rm -rf .tmp_versions Modules.symvers + +deploy: all + scp $(modulename).ko "$(DEPLOYSSH):$(DEPLOYSSHPATH)/$(modulename).ko" + ssh $(DEPLOYSSH) "rmmod $(modulename)"; + ssh $(DEPLOYSSH) "insmod $(DEPLOYSSHPATH)/$(modulename).ko"; + + +.PHONY: all clean deploy diff --git a/drivers/infrared/infrared.c b/drivers/infrared/infrared.c new file mode 100644 index 0000000..8c73907 --- /dev/null +++ b/drivers/infrared/infrared.c @@ -0,0 +1,265 @@ +/* + * Terasic DE1-SoC Sensor Driver for Infrared (IR) Sensor + * + * Copyright (C) 2020 Michael Wurm + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 and + * only version 2 as published by the Free Software Foundation. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define DRIVER_NAME "infrared" + +#define SIGNAL_EVENT 12 // User space has to listen for this event number (SIGUSR2) + +#define NUM_TIMESTAMPS 256 +#define NUM_BYTE_TIMESTAMP_DATA (NUM_TIMESTAMPS * sizeof(uint32_t)) +#define NUM_BYTE_MAGIC_NRS (4 * sizeof(uint32_t)) +#define NUM_BYTE_IRQS_ACTIVE (sizeof(uint32_t)) + +#define SIZEOF_DATA_T (NUM_BYTE_TIMESTAMP_DATA + \ + NUM_BYTE_MAGIC_NRS) + +#define MEM_OFFSET_DATA_MAGIC_NR0 (NUM_BYTE_TIMESTAMP_DATA + 0x0) +#define MEM_OFFSET_DATA_MAGIC_NR1 (NUM_BYTE_TIMESTAMP_DATA + 0x4) +#define MEM_OFFSET_DATA_MAGIC_NR2 (NUM_BYTE_TIMESTAMP_DATA + 0x8) +#define MEM_OFFSET_DATA_MAGIC_NR3 (NUM_BYTE_TIMESTAMP_DATA + 0xC) +#define MEM_OFFSET_DATA_IRQ (NUM_BYTE_TIMESTAMP_DATA + 0x10) + +/* IO Control (IOCTL) */ +#define IOC_SET_PID 0 +#define IOC_CMD_SET_PID _IO(4711, IOC_SET_PID) + +typedef struct +{ + uint32_t timestamp[NUM_TIMESTAMPS]; + uint32_t magic_number[4]; +} __attribute__((packed)) buffer_t; + +struct data +{ + void *regs; + buffer_t buffer_data; + uint32_t pid; + uint32_t mode; + uint32_t size; + uint32_t irq_nr; + uint32_t irq_count; + uint32_t irqs_active; + struct miscdevice misc; +}; + +static irqreturn_t irq_handler(int nr, void *data_ptr) +{ + struct data *dev = data_ptr; + struct siginfo info; + struct task_struct *t; + + pr_info("INFRARED Interrupt occured.\n"); + + /* Determine which interrupt occured */ + dev->irqs_active = ioread32(dev->regs + MEM_OFFSET_DATA_IRQ); + + if (dev->irqs_active == 0x1) + { + dev->irq_count++; + pr_info("INFRARED Received interrupt [Occured %i times so far.]\n", dev->irq_count); + } + else + { + /* Another device asserted the shared interrupt line */ + pr_info("INFRARED Shared interrupt wasn't me."); + return IRQ_NONE; + } + + /* Send signal to user space */ + t = pid_task(find_vpid(dev->pid), PIDTYPE_PID); + if (t == NULL) + { + printk(KERN_ERR "A Task with PID %i does not exist.\n", dev->pid); + return IRQ_HANDLED; + } + + memset(&info, 0, sizeof(struct siginfo)); + info.si_signo = SIGNAL_EVENT; + info.si_code = SI_QUEUE; + info.si_int = 4711; + + send_sig_info(SIGNAL_EVENT, &info, t); + + return IRQ_HANDLED; +} + +/* + * @brief This function gets executed on fread. + */ +static int dev_read(struct file *filep, char *buf, size_t count, + loff_t *offp) +{ + struct data *dev = container_of(filep->private_data, + struct data, misc); + int i; + + if (SIZEOF_DATA_T != sizeof(dev->buffer_data)) + { + printk(KERN_ERR "Data struct buffer_t is not allocated as expected.\n"); + return -ENOEXEC; + } + + /* check out of bound access */ + if ((*offp < 0) || (*offp >= SIZEOF_DATA_T)) + return 0; + + /* limit number of readable bytes to maximum which is still possible */ + if ((*offp + count) > SIZEOF_DATA_T) + count = SIZEOF_DATA_T - *offp; + + // Read timestamps from FPGA RAM + for (i = 0; i < NUM_TIMESTAMPS; i++) + { + dev->buffer_data.timestamp[i] = ioread32(dev->regs + i * 4); + } + + dev->buffer_data.magic_number[0] = ioread32(dev->regs + MEM_OFFSET_DATA_MAGIC_NR0); + dev->buffer_data.magic_number[1] = ioread32(dev->regs + MEM_OFFSET_DATA_MAGIC_NR1); + dev->buffer_data.magic_number[2] = ioread32(dev->regs + MEM_OFFSET_DATA_MAGIC_NR2); + dev->buffer_data.magic_number[3] = ioread32(dev->regs + MEM_OFFSET_DATA_MAGIC_NR3); + + /* copy data from kernel space buffer into user space */ + if (count > 0) + count = count - copy_to_user(buf, (char *)&dev->buffer_data + *offp, count); + + *offp += count; + + return count; +} + +/* + * @brief This function gets executed on ioctl. + */ +static long dev_ioctl(struct file *filep, unsigned int cmd, unsigned long arg) +{ + struct data *dev = container_of(filep->private_data, struct data, misc); + + switch (cmd) + { + case IOC_CMD_SET_PID: + /* Get the PID of the currently executing process. + * The `current` variable is defined in linux/sched/signal.h */ + dev->pid = task_pid_nr(current); + pr_info("dev_ioctl: Set current PID to %i.\n", dev->pid); + break; + default: + /* it seems like ioctl is also called for all invocations of fread with cmd 0x5041 (TCGETS) */ + // pr_info("dev_ioctl: Unknown cmd (%u). Exit.\n", cmd); + break; + } + return 0; +} + +static const struct file_operations dev_fops = { + .owner = THIS_MODULE, + .read = dev_read, + .unlocked_ioctl = dev_ioctl}; + +static int dev_probe(struct platform_device *pdev) +{ + struct data *dev; + struct resource *io; + int retval; + + /* Allocate memory for private data */ + dev = devm_kzalloc(&pdev->dev, sizeof(*dev), GFP_KERNEL); + if (dev == NULL) + return -ENOMEM; + platform_set_drvdata(pdev, dev); + + /* Get resources */ + io = platform_get_resource(pdev, IORESOURCE_MEM, 0); + dev->regs = devm_ioremap_resource(&pdev->dev, io); + if (IS_ERR(dev->regs)) + return PTR_ERR(dev->regs); + + dev->size = io->end - io->start + 1; + dev->misc.name = DRIVER_NAME; + dev->misc.minor = MISC_DYNAMIC_MINOR; + dev->misc.fops = &dev_fops; + dev->misc.parent = &pdev->dev; + retval = misc_register(&dev->misc); + if (retval) + { + dev_err(&pdev->dev, "Register misc device failed!\n"); + return retval; + } + + /* Get interrupt */ + dev->irq_nr = platform_get_irq(pdev, 0); + retval = devm_request_irq(&pdev->dev, dev->irq_nr, &irq_handler, + IRQF_SHARED, dev_name(&pdev->dev), dev); + if (retval != 0) + { + dev_err(&pdev->dev, "Request interrupt failed!\n"); + return retval; + } + + /* Enable interrupt generation in FPGA device */ + // iowrite32(0x3, dev->regs + MEM_OFFSET_BUF_IEN); + + dev_info(&pdev->dev, "Infrared (IR) sensor driver loaded!"); + + return 0; +} + +static int dev_remove(struct platform_device *pdev) +{ + struct data *dev = platform_get_drvdata(pdev); + + /* Disable interrupt generation in FPGA device */ + // iowrite32(0x0, dev->regs + MEM_OFFSET_BUF_IEN); + devm_free_irq(&pdev->dev, dev->irq_nr, dev); + + misc_deregister(&dev->misc); + platform_set_drvdata(pdev, NULL); + + return 0; +} + +static const struct of_device_id dev_of_match[] = { + { + .compatible = "wur,infrared-1.0", + }, + {}, +}; +MODULE_DEVICE_TABLE(of, dev_of_match); + +static struct platform_driver dev_driver = { + .driver = { + .name = DRIVER_NAME, + .owner = THIS_MODULE, + .of_match_table = of_match_ptr(dev_of_match), + }, + .probe = dev_probe, + .remove = dev_remove, +}; + +module_platform_driver(dev_driver); + +MODULE_AUTHOR("M.Wurm"); +MODULE_DESCRIPTION("Altera/Terasic Infrared (IR) sensor driver"); +MODULE_LICENSE("GPL v2"); diff --git a/drivers/mpu9250/mpu9250.c b/drivers/mpu9250/mpu9250.c index 45e278d..879451d 100644 --- a/drivers/mpu9250/mpu9250.c +++ b/drivers/mpu9250/mpu9250.c @@ -26,7 +26,7 @@ #define DRIVER_NAME "mpu9250" -#define SIGNAL_EVENT 10 // User space has to listen for this event number +#define SIGNAL_EVENT 10 // User space has to listen for this event number (SIGUSR1) #define NUM_BYTE_SENSOR_DATA (3 * 3 * sizeof(uint16_t)) #define NUM_BYTE_TIMESTAMP (2 * sizeof(uint32_t)) diff --git a/hdl/HPSPlatform.qsys b/hdl/HPSPlatform.qsys index 0643f77..ebce3bd 100644 --- a/hdl/HPSPlatform.qsys +++ b/hdl/HPSPlatform.qsys @@ -161,6 +161,14 @@ type = "String"; } } + element HPSPlatform + { + datum _originalDeviceFamily + { + value = "Cyclone V"; + type = "String"; + } + } element clk_0 { datum _sortIndex @@ -177,6 +185,19 @@ type = "int"; } } + element hmi.infrared_s0 + { + datum _lockedAddress + { + value = "1"; + type = "boolean"; + } + datum baseAddress + { + value = "8192"; + type = "String"; + } + } element hmi.leds_s1 { datum _lockedAddress @@ -184,6 +205,11 @@ value = "1"; type = "boolean"; } + datum _tags + { + value = ""; + type = "String"; + } datum baseAddress { value = "1040"; @@ -279,6 +305,22 @@ + + + + - + @@ -378,6 +420,9 @@ + + + @@ -398,9 +443,9 @@ - + - + @@ -932,7 +977,16 @@ + + + + + @@ -941,7 +995,7 @@ @@ -950,7 +1004,7 @@ @@ -959,7 +1013,7 @@ @@ -968,7 +1022,7 @@ @@ -977,7 +1031,7 @@ @@ -986,76 +1040,93 @@ - + + - + + + + + diff --git a/hdl/components/infrared/comp.do b/hdl/components/infrared/comp.do new file mode 100644 index 0000000..0552287 --- /dev/null +++ b/hdl/components/infrared/comp.do @@ -0,0 +1,21 @@ + +#----------------------------------*-tcl-*- + +#------------------------------------------- +proc myvcom {filename} { + if {[file exists ${filename}] == 1} { + puts "## vcom $filename" + vcom -93 -novopt -quiet ${filename} -work work + } else { + puts "## WARNING: File not found: ${filename}" + } +} + +#------------------------------------------- +vlib work +myvcom counter.vhd +myvcom sync.vhd +myvcom sync_single.vhd +myvcom infrared_sender.vhd +myvcom infrared.vhd +myvcom tb_infrared.vhd diff --git a/hdl/components/infrared/comp_sim.do b/hdl/components/infrared/comp_sim.do new file mode 100644 index 0000000..76b1238 --- /dev/null +++ b/hdl/components/infrared/comp_sim.do @@ -0,0 +1,22 @@ +#----------------------------------*-tcl-*- +do comp.do + +echo "Sim: load design" +set unit tb_infrared +vsim -novopt -wlfdeleteonquit \ + work.${unit}(Bhv) \ + +nowarn3116 + +set tb ${unit} +set dut ${tb}/DUT + +echo "Sim: load wave-file(s)" +catch {do wave.do} + +echo "Sim: log signals" +log -r /* + +echo "Sim: run ..." +run 100 us + +catch {do wave-restore.do} diff --git a/hdl/components/infrared/counter.vhd b/hdl/components/infrared/counter.vhd new file mode 100644 index 0000000..d13a626 --- /dev/null +++ b/hdl/components/infrared/counter.vhd @@ -0,0 +1,114 @@ +------------------------------------------------------------------------------- +--! @file counter.vhd +--! @author Michael Wurm +--! @copyright 2020 Michael Wurm +--! @brief Entity implementation of counter. +------------------------------------------------------------------------------- + +library ieee; +use ieee.std_logic_1164.all; +use ieee.numeric_std.all; + +--! @brief Entity declaration of counter +--! @details +--! Provides a counter value of clock ticks of clk_i. +--! The counter is free-running, and thus overflows at its maximum. + +entity counter is + generic ( + counter_width_g : natural := 32); + port ( + --! @name Clocks and resets + --! @{ + + --! System clock + clk_i : in std_ulogic; + --! Asynchronous reset + rst_n_i : in std_ulogic; + + --! @} + --! @name Control and status signals + --! @{ + + --! Enable + enable_i : in std_ulogic; + --! Overflow + overflow_o : out std_ulogic; + --! Generated strobe + count_o : out unsigned(counter_width_g-1 downto 0)); + + --! @} + +end entity counter; + +--! RTL implementation of counter +architecture rtl of counter is + + ----------------------------------------------------------------------------- + --! @name Types and Constants + ----------------------------------------------------------------------------- + --! @{ + + constant max_count_c : unsigned(count_o'range) := (others => '1'); + + --! @} + + ----------------------------------------------------------------------------- + --! @name Internal Registers + ----------------------------------------------------------------------------- + --! @{ + + signal count : unsigned(count_o'range); + signal overflow : std_ulogic := '0'; + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Wires + ----------------------------------------------------------------------------- + --! @{ + + + --! @} + +begin -- architecture rtl + + ------------------------------------------------------------------------------ + -- Outputs + ------------------------------------------------------------------------------ + + count_o <= count; + overflow_o <= overflow; + + ----------------------------------------------------------------------------- + -- Signal Assignments + ----------------------------------------------------------------------------- + + ------------------------------------------------------------------------------ + -- Registers + ------------------------------------------------------------------------------ + + regs : process (clk_i, rst_n_i) is + procedure reset is + begin + count <= to_unsigned(0, count'length); + overflow <= '0'; + end procedure reset; + begin -- process regs + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + -- Defaults + overflow <= '0'; + + if enable_i = '0' then + reset; + else + count <= count + 1; + if count = max_count_c then + overflow <= '1'; + end if; + end if; + end if; + end process regs; + +end architecture rtl; diff --git a/hdl/components/infrared/infrared.vhd b/hdl/components/infrared/infrared.vhd new file mode 100644 index 0000000..b95dc98 --- /dev/null +++ b/hdl/components/infrared/infrared.vhd @@ -0,0 +1,259 @@ +------------------------------------------------------------------------------- +--! @file infrared.vhd +--! @author Michael Wurm +--! @copyright 2020 Michael Wurm +--! @brief Entity implementation of infrared. +------------------------------------------------------------------------------- + +library ieee; +use ieee.std_logic_1164.all; +use ieee.numeric_std.all; + +--! @brief Entity declaration of infrared +--! @details +--! Stores timestamps on every change of the IR LED input. +--! In that way, a sequence can be recorded and reproduced afterwards. + +entity infrared is + port ( + --! @name Clocks and resets + --! @{ + + --! System clock + clk_i : in std_logic; + --! Asynchronous reset + rst_n_i : in std_logic; + + --! @} + --! @name Avalon MM Bus + --! @{ + avs_s0_address : in std_logic_vector(10 downto 0); + avs_s0_read : in std_logic; + avs_s0_readdata : out std_logic_vector(31 downto 0); + avs_s0_write : in std_logic; + avs_s0_writedata : in std_logic_vector(31 downto 0); + + --! @} + --! @name Infrared transceiver signals + --! @{ + + --! IR Receive + ir_rx_i : in std_logic; + --! IR Transmit + ir_tx_o : out std_logic; + + --! @} + --! @name Status signals + --! @{ + + --! Done recording interrupt + done_recording_irq_o : out std_logic; + --! IR Receive Mirror + ir_rx_o : out std_logic); + + --! @} + +end entity infrared; + +--! RTL implementation of infrared +architecture rtl of infrared is + ----------------------------------------------------------------------------- + --! @name Types and Constants + ----------------------------------------------------------------------------- + --! @{ + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Registers + ----------------------------------------------------------------------------- + --! @{ + + subtype timestamp_t is unsigned(31 downto 0); + type ram_t is array(0 to 255) of timestamp_t; + + signal ram_data : ram_t := (others => (others => '0')); + signal ram_readdata : timestamp_t := (others => '0'); + signal ctrl_readdata : timestamp_t := (others => '0'); + + signal ram_addr : unsigned(7 downto 0) := (others => '0'); + signal ir_rx : std_ulogic_vector(1 downto 0) := (others => '0'); + signal store_timestamp : std_ulogic := '0'; + signal irq_active : std_ulogic := '0'; + signal irq_reset : std_ulogic := '0'; + signal start_replay : std_ulogic := '0'; + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Wires + ----------------------------------------------------------------------------- + --! @{ + + signal ir_rx_sync : std_ulogic; + signal next_ir_rx : std_ulogic_vector(1 downto 0); + signal rising : std_ulogic; + signal falling : std_ulogic; + signal recording_stopped : std_ulogic; + signal timestamp : timestamp_t; + signal ctrl_access : std_ulogic; + signal end_of_sequence : std_ulogic; + signal ctrl_addr : unsigned(avs_s0_address'high downto ram_addr'high+1); + + signal ir_tx : std_ulogic; + signal done_replay : std_ulogic; + signal replay_running: std_ulogic; + + --! @} + +begin -- architecture rtl + + ------------------------------------------------------------------------------ + -- Outputs + ------------------------------------------------------------------------------ + + ir_rx_o <= ir_rx(ir_rx'high); -- mirror rx signal (for debug only) + ir_tx_o <= ir_tx; + avs_s0_readdata <= std_logic_vector(ram_readdata) when ctrl_access = '0' + else std_logic_vector(ctrl_readdata); + done_recording_irq_o <= irq_active; + + ----------------------------------------------------------------------------- + -- Signal Assignments + ----------------------------------------------------------------------------- + + next_ir_rx <= ir_rx(ir_rx'high-1 downto ir_rx'low) & ir_rx_sync; + rising <= '1' when ir_rx(1)='0' and ir_rx(0)='1' else '0'; + falling <= '1' when ir_rx(1)='1' and ir_rx(0)='0' else '0'; + ctrl_access <= '1' when to_integer(unsigned(avs_s0_address)) > ram_t'length-1 else '0'; + end_of_sequence <= '1' when to_integer(ram_addr) > 5 and ir_rx(1) = '1' else '0'; + ctrl_addr <= unsigned(avs_s0_address(ctrl_addr'range)); + + ----------------------------------------------------------------------------- + -- Instantiations + ----------------------------------------------------------------------------- + + sync_inst : entity work.sync_single + generic map ( + init_value_g => '0', + num_delays_g => 2) + port map ( + clk_i => clk_i, + rst_n_i => rst_n_i, + async_i => ir_rx_i, + sync_o => ir_rx_sync); + + timestamp_counter_inst : entity work.counter + generic map ( + counter_width_g => 32) + port map ( + clk_i => clk_i, + rst_n_i => rst_n_i, + enable_i => '1', + overflow_o => open, + count_o => timestamp); + + stop_counter_inst : entity work.counter + generic map ( + counter_width_g => 10) -- 2^25 steps @ 50MHz => 0.6711 sec + port map ( + clk_i => clk_i, + rst_n_i => rst_n_i, + enable_i => end_of_sequence, + overflow_o => recording_stopped, + count_o => open); + + sender_inst : entity work.infrared_sender + port map ( + clk_i => clk_i, + rst_n_i => rst_n_i, + + avs_s0_address => avs_s0_address, + avs_s0_read => avs_s0_read, + avs_s0_readdata => open, + avs_s0_write => avs_s0_write, + avs_s0_writedata => avs_s0_writedata, + + ir_tx_o => ir_tx, + replay_running_o => replay_running, + done_replay_o => done_replay); + + ------------------------------------------------------------------------------ + -- Registers + ------------------------------------------------------------------------------ + + regs : process (clk_i, rst_n_i) is + procedure reset is + begin + ram_addr <= to_unsigned(0, ram_addr'length); + store_timestamp <= '0'; + irq_active <= '0'; + end procedure reset; + begin -- process strobe + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + -- Defaults + ir_rx <= next_ir_rx; + store_timestamp <= '0'; + + if rising = '1' or falling = '1' then + ram_addr <= ram_addr + 1; + store_timestamp <= '1'; + elsif recording_stopped = '1' then + irq_active <= '1'; + ram_addr <= (others => '0'); + end if; + if irq_reset = '1' then + irq_active <= '0'; + end if; + end if; + end process regs; + + ram : process (clk_i) is + begin + if rising_edge(clk_i) then + if store_timestamp = '1' then + ram_data(to_integer(ram_addr)) <= timestamp; + end if; + + if avs_s0_read = '1' then + ram_readdata <= ram_data(to_integer(unsigned(avs_s0_address(ram_addr'range)))); + end if; + end if; + end process ram; + + ctrl_interface : process (clk_i) is + procedure reset is + begin + ctrl_readdata <= (others => '0'); + irq_reset <= '0'; + end procedure reset; + begin -- process ctrl_interface + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + if avs_s0_read = '1' then + -- Defaults + ctrl_readdata <= (others => '0'); + irq_reset <= '0'; + + -- addresses lower 255 are reserved for RAM + case (to_integer(unsigned(avs_s0_address))) is + when 256 => -- magic number + ctrl_readdata <= x"ABCD1234"; + when 257 => -- magic number + ctrl_readdata <= x"10101010"; + when 258 => -- magic number + ctrl_readdata <= x"22222222"; + when 259 => -- magic number + ctrl_readdata <= x"33333333"; + when 260 => -- read and clear irq status + ctrl_readdata(0) <= irq_active; + irq_reset <= '1'; + when others => + ctrl_readdata <= x"DEADBEEF"; + end case; + end if; + end if; + end process ctrl_interface; + +end architecture rtl; diff --git a/hdl/components/infrared/infrared_hw.tcl b/hdl/components/infrared/infrared_hw.tcl new file mode 100644 index 0000000..77b44ce --- /dev/null +++ b/hdl/components/infrared/infrared_hw.tcl @@ -0,0 +1,200 @@ +# TCL File Generated by Component Editor 19.1 +# Mon Feb 24 13:39:53 CET 2020 +# DO NOT MODIFY + + +# +# infrared "infrared" v1.0 +# Michael Wurm 2020.02.24.13:39:53 +# Infrared Recorder/Transmitter +# + +# +# request TCL package from ACDS 16.1 +# +package require -exact qsys 16.1 + + +# +# module infrared +# +set_module_property DESCRIPTION "Infrared Recorder/Transmitter" +set_module_property NAME infrared +set_module_property VERSION 1.0 +set_module_property INTERNAL false +set_module_property OPAQUE_ADDRESS_MAP true +set_module_property AUTHOR "Michael Wurm" +set_module_property DISPLAY_NAME infrared +set_module_property INSTANTIATE_IN_SYSTEM_MODULE true +set_module_property EDITABLE true +set_module_property REPORT_TO_TALKBACK false +set_module_property ALLOW_GREYBOX_GENERATION false +set_module_property REPORT_HIERARCHY false + + +# +# file sets +# +add_fileset QUARTUS_SYNTH QUARTUS_SYNTH "" "" +set_fileset_property QUARTUS_SYNTH TOP_LEVEL infrared +set_fileset_property QUARTUS_SYNTH ENABLE_RELATIVE_INCLUDE_PATHS false +set_fileset_property QUARTUS_SYNTH ENABLE_FILE_OVERWRITE_MODE false +add_fileset_file counter.vhd VHDL PATH counter.vhd +add_fileset_file sync_single.vhd VHDL PATH sync_single.vhd +add_fileset_file infrared.vhd VHDL PATH infrared.vhd TOP_LEVEL_FILE + +add_fileset SIM_VHDL SIM_VHDL "" "" +set_fileset_property SIM_VHDL TOP_LEVEL infrared +set_fileset_property SIM_VHDL ENABLE_RELATIVE_INCLUDE_PATHS false +set_fileset_property SIM_VHDL ENABLE_FILE_OVERWRITE_MODE true +add_fileset_file counter.vhd VHDL PATH counter.vhd +add_fileset_file sync_single.vhd VHDL PATH sync_single.vhd +add_fileset_file infrared.vhd VHDL PATH infrared.vhd + + +# +# parameters +# + + +# +# module assignments +# +set_module_assignment embeddedsw.dts.group sensor +set_module_assignment embeddedsw.dts.name infrared +set_module_assignment embeddedsw.dts.vendor wur + + +# +# display items +# + + +# +# connection point s0 +# +add_interface s0 avalon end +set_interface_property s0 addressUnits WORDS +set_interface_property s0 associatedClock clk_i +set_interface_property s0 associatedReset rst_n_i +set_interface_property s0 bitsPerSymbol 8 +set_interface_property s0 burstOnBurstBoundariesOnly false +set_interface_property s0 burstcountUnits WORDS +set_interface_property s0 explicitAddressSpan 0 +set_interface_property s0 holdTime 0 +set_interface_property s0 linewrapBursts false +set_interface_property s0 maximumPendingReadTransactions 0 +set_interface_property s0 maximumPendingWriteTransactions 0 +set_interface_property s0 readLatency 0 +set_interface_property s0 readWaitTime 1 +set_interface_property s0 setupTime 0 +set_interface_property s0 timingUnits Cycles +set_interface_property s0 writeWaitTime 0 +set_interface_property s0 ENABLED true +set_interface_property s0 EXPORT_OF "" +set_interface_property s0 PORT_NAME_MAP "" +set_interface_property s0 CMSIS_SVD_VARIABLES "" +set_interface_property s0 SVD_ADDRESS_GROUP "" + +add_interface_port s0 avs_s0_address address Input 11 +add_interface_port s0 avs_s0_read read Input 1 +add_interface_port s0 avs_s0_readdata readdata Output 32 +add_interface_port s0 avs_s0_write write Input 1 +add_interface_port s0 avs_s0_writedata writedata Input 32 +set_interface_assignment s0 embeddedsw.configuration.isFlash 0 +set_interface_assignment s0 embeddedsw.configuration.isMemoryDevice 0 +set_interface_assignment s0 embeddedsw.configuration.isNonVolatileStorage 0 +set_interface_assignment s0 embeddedsw.configuration.isPrintableDevice 0 + + +# +# connection point clk_i +# +add_interface clk_i clock end +set_interface_property clk_i clockRate 0 +set_interface_property clk_i ENABLED true +set_interface_property clk_i EXPORT_OF "" +set_interface_property clk_i PORT_NAME_MAP "" +set_interface_property clk_i CMSIS_SVD_VARIABLES "" +set_interface_property clk_i SVD_ADDRESS_GROUP "" + +add_interface_port clk_i clk_i clk Input 1 + + +# +# connection point rst_n_i +# +add_interface rst_n_i reset end +set_interface_property rst_n_i associatedClock clk_i +set_interface_property rst_n_i synchronousEdges DEASSERT +set_interface_property rst_n_i ENABLED true +set_interface_property rst_n_i EXPORT_OF "" +set_interface_property rst_n_i PORT_NAME_MAP "" +set_interface_property rst_n_i CMSIS_SVD_VARIABLES "" +set_interface_property rst_n_i SVD_ADDRESS_GROUP "" + +add_interface_port rst_n_i rst_n_i reset_n Input 1 + + +# +# connection point done_recording_irq +# +add_interface done_recording_irq interrupt end +set_interface_property done_recording_irq associatedAddressablePoint "" +set_interface_property done_recording_irq associatedClock clk_i +set_interface_property done_recording_irq associatedReset rst_n_i +set_interface_property done_recording_irq bridgedReceiverOffset "" +set_interface_property done_recording_irq bridgesToReceiver "" +set_interface_property done_recording_irq ENABLED true +set_interface_property done_recording_irq EXPORT_OF "" +set_interface_property done_recording_irq PORT_NAME_MAP "" +set_interface_property done_recording_irq CMSIS_SVD_VARIABLES "" +set_interface_property done_recording_irq SVD_ADDRESS_GROUP "" + +add_interface_port done_recording_irq done_recording_irq_o irq Output 1 + + +# +# connection point ir_rx_i +# +add_interface ir_rx_i conduit end +set_interface_property ir_rx_i associatedClock clk_i +set_interface_property ir_rx_i associatedReset "" +set_interface_property ir_rx_i ENABLED true +set_interface_property ir_rx_i EXPORT_OF "" +set_interface_property ir_rx_i PORT_NAME_MAP "" +set_interface_property ir_rx_i CMSIS_SVD_VARIABLES "" +set_interface_property ir_rx_i SVD_ADDRESS_GROUP "" + +add_interface_port ir_rx_i ir_rx_i conduit Input 1 + + +# +# connection point ir_rx_o +# +add_interface ir_rx_o conduit end +set_interface_property ir_rx_o associatedClock clk_i +set_interface_property ir_rx_o associatedReset "" +set_interface_property ir_rx_o ENABLED true +set_interface_property ir_rx_o EXPORT_OF "" +set_interface_property ir_rx_o PORT_NAME_MAP "" +set_interface_property ir_rx_o CMSIS_SVD_VARIABLES "" +set_interface_property ir_rx_o SVD_ADDRESS_GROUP "" + +add_interface_port ir_rx_o ir_rx_o conduit Output 1 + + +# +# connection point ir_tx_o +# +add_interface ir_tx_o conduit end +set_interface_property ir_tx_o associatedClock clk_i +set_interface_property ir_tx_o associatedReset "" +set_interface_property ir_tx_o ENABLED true +set_interface_property ir_tx_o EXPORT_OF "" +set_interface_property ir_tx_o PORT_NAME_MAP "" +set_interface_property ir_tx_o CMSIS_SVD_VARIABLES "" +set_interface_property ir_tx_o SVD_ADDRESS_GROUP "" + +add_interface_port ir_tx_o ir_tx_o conduit Output 1 + diff --git a/hdl/components/infrared/infrared_sender.vhd b/hdl/components/infrared/infrared_sender.vhd new file mode 100644 index 0000000..80bb434 --- /dev/null +++ b/hdl/components/infrared/infrared_sender.vhd @@ -0,0 +1,204 @@ +------------------------------------------------------------------------------- +--! @file infrared_sender.vhd +--! @author Michael Wurm +--! @copyright 2020 Michael Wurm +--! @brief Implementation of infrared_sender. +------------------------------------------------------------------------------- + +library ieee; +use ieee.std_logic_1164.all; +use ieee.numeric_std.all; + +--! @brief Entity declaration of infrared_sender +--! @details +--! Implements an interface to receive timestamps and store them. +--! The IR output signal changes, whenever the local time matches a timestamp. + +entity infrared_sender is + port ( + --! @name Clocks and resets + --! @{ + + --! System clock + clk_i : in std_ulogic; + --! Asynchronous reset + rst_n_i : in std_ulogic; + + --! @} + --! @name Avalon MM Bus + --! @{ + avs_s0_address : in std_logic_vector(10 downto 0); + avs_s0_read : in std_logic; + avs_s0_readdata : out std_logic_vector(31 downto 0); + avs_s0_write : in std_logic; + avs_s0_writedata : in std_logic_vector(31 downto 0); + + --! @} + --! @name Infrared transmitter signals + --! @{ + + --! IR transmitter signel + ir_tx_o : out std_ulogic; + + --! @} + --! @name Status signals + --! @{ + + --! Done replaying of IR sequence + done_replay_o : out std_ulogic; + --! Replay of IR sequence running + replay_running_o : out std_ulogic); + + --! @} + +end entity infrared_sender; + +--! RTL implementation of infrared_sender +architecture rtl of infrared_sender is + + ----------------------------------------------------------------------------- + --! @name Types and Constants + ----------------------------------------------------------------------------- + --! @{ + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Registers + ----------------------------------------------------------------------------- + --! @{ + + subtype timestamp_t is unsigned(31 downto 0); + type ram_t is array(0 to 255) of timestamp_t; + + signal ram_data : ram_t := (others => (others => '0')); + signal ram_readdata : timestamp_t := (others => '0'); + signal ram_addr : unsigned(7 downto 0) := (others => '0'); + + signal start_replay : std_ulogic := '0'; + signal replay_done : std_ulogic := '0'; + signal replay_running : std_ulogic := '0'; + signal ir_tx : std_ulogic := '0'; + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Wires + ----------------------------------------------------------------------------- + --! @{ + + signal timestamp : timestamp_t; + signal end_of_sequence : std_ulogic; + signal timestamp_match : std_ulogic; + signal ctrl_access : std_ulogic; + + --! @} + +begin -- architecture rtl + + ------------------------------------------------------------------------------ + -- Outputs + ------------------------------------------------------------------------------ + + done_replay_o <= replay_done; + replay_running_o <= replay_running; + ir_tx_o <= ir_tx; + + ----------------------------------------------------------------------------- + -- Signal Assignments + ----------------------------------------------------------------------------- + + timestamp_match <= '1' when timestamp = ram_readdata and + replay_running = '1' + else '0'; + end_of_sequence <= '1' when to_integer(ram_addr) > 5 and + ram_readdata = to_unsigned(0, ram_addr'length) + else '0'; + ctrl_access <= '1' when to_integer(unsigned(avs_s0_address)) > ram_t'length-1 + else '0'; + + ----------------------------------------------------------------------------- + -- Instantiations + ----------------------------------------------------------------------------- + + timestamp_counter_inst : entity work.counter + generic map ( + counter_width_g => 32) + port map ( + clk_i => clk_i, + rst_n_i => rst_n_i, + enable_i => replay_running, + overflow_o => open, + count_o => timestamp); + + ------------------------------------------------------------------------------ + -- Registers + ------------------------------------------------------------------------------ + + regs : process (clk_i, rst_n_i) is + procedure reset is + begin + ram_addr <= to_unsigned(0, ram_addr'length); + replay_running <= '0'; + replay_done <= '0'; + ir_tx <= '1'; -- default IR signal value + end procedure reset; + begin -- process strobe + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + -- Defaults + + if start_replay = '1' and replay_running = '0' then + replay_running <= '1'; + replay_done <= '0'; + end if; + + if timestamp_match = '1' then + ram_addr <= ram_addr + 1; + ir_tx <= not ir_tx; -- toggle IR signal with a timestamp match + end if; + + if end_of_sequence = '1' then + ram_addr <= to_unsigned(0, ram_addr'length); + replay_running <= '0'; + replay_done <= '1'; + end if; + end if; + end process regs; + + ram : process (clk_i) is + begin + if rising_edge(clk_i) then + if avs_s0_write = '1' and ctrl_access = '0' then + ram_data(to_integer(unsigned(avs_s0_address(ram_addr'range)))) <= + unsigned(avs_s0_writedata); + end if; + + ram_readdata <= ram_data(to_integer(unsigned(ram_addr(ram_addr'range)))); + end if; + end process ram; + + ctrl_interface : process (clk_i) is + procedure reset is + begin + start_replay <= '0'; + end procedure reset; + begin -- process ctrl_interface + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + if end_of_sequence = '1' then + start_replay <= '0'; + end if; + + if avs_s0_write = '1' and ctrl_access = '1' then + -- addresses lower 255 are reserved for RAM + case (to_integer(unsigned(avs_s0_address))) is + when 256 => + start_replay <= std_ulogic(avs_s0_writedata(0)); + when others => null; + end case; + end if; + end if; + end process ctrl_interface; + +end architecture rtl; diff --git a/hdl/components/infrared/modelsim_sim.sh b/hdl/components/infrared/modelsim_sim.sh new file mode 100755 index 0000000..df54e73 --- /dev/null +++ b/hdl/components/infrared/modelsim_sim.sh @@ -0,0 +1,4 @@ +#!/usr/bin/env bash + +#vsim -do comp.do -c +vsim -do comp_sim.do diff --git a/hdl/components/infrared/strobe_gen.vhd b/hdl/components/infrared/strobe_gen.vhd new file mode 100644 index 0000000..004bf7e --- /dev/null +++ b/hdl/components/infrared/strobe_gen.vhd @@ -0,0 +1,119 @@ +------------------------------------------------------------------------------- +--! @file strobe_gen.vhd +--! @author Michael Wurm +--! @copyright 2020 Michael Wurm +--! @brief Entity implementation of strobe_gen. +------------------------------------------------------------------------------- + +library ieee; +use ieee.std_logic_1164.all; +use ieee.numeric_std.all; + +--! @brief Entity declaration of strobe_gen +--! @details +--! Generates a strobe signal that will be '1' for one clock cycle +--! of clk_i. The strobe comes every period_g. If this cycle time +--! cannot be generated exactly it will be truncated with the +--! accuracy of one clk_i cycle. + +entity strobe_gen is + generic ( + --! System clock frequency + clk_freq_g : natural := clk_freq_c; + --! Period between two strobes + period_g : time := 100 us); + port ( + --! @name Clocks and resets + --! @{ + + --! System clock + clk_i : in std_ulogic; + --! Asynchronous reset + rst_n_i : in std_ulogic; + + --! @} + --! @name Strobe signals + --! @{ + + --! Enable + enable_i : in std_ulogic; + --! Generated strobe + strobe_o : out std_ulogic); + + --! @} + +begin + + -- pragma translate_off + assert ((1 sec / clk_freq_g) <= period_g) + report "strobe_gen: The Clk frequency is to low to generate such a short strobe cycle." + severity error; + -- pragma translate_on + +end entity strobe_gen; + +--! RTL implementation of strobe_gen +architecture rtl of strobe_gen is + ----------------------------------------------------------------------------- + --! @name Types and Constants + ----------------------------------------------------------------------------- + --! @{ + + constant clks_per_strobe_c : natural := clk_freq_g / (1 sec / period_g); + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Registers + ----------------------------------------------------------------------------- + --! @{ + + signal count : unsigned(log_dualis(clks_per_strobe_c) downto 0); + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Wires + ----------------------------------------------------------------------------- + --! @{ + + signal strobe : std_ulogic; + + --! @} + +begin -- architecture rtl + + ------------------------------------------------------------------------------ + -- Outputs + ------------------------------------------------------------------------------ + + strobe_o <= strobe; + + ------------------------------------------------------------------------------ + -- Registers + ------------------------------------------------------------------------------ + + -- Count the number of clk_i cycles from strobe pulse to strobe pulse. + regs : process (clk_i, rst_n_i) is + procedure reset is + begin + count <= to_unsigned(0, count'length); + strobe <= '0'; + end procedure reset; + begin -- process strobe + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + if enable_i = '0' then + reset; + else + if count = clks_per_strobe_c-1 then + count <= (others => '0'); + strobe <= '1'; + else + count <= count + 1; + strobe <= '0'; + end if; + end if; + end if; + end process regs; + +end architecture rtl; diff --git a/hdl/components/infrared/sync.vhd b/hdl/components/infrared/sync.vhd new file mode 100644 index 0000000..b1a5245 --- /dev/null +++ b/hdl/components/infrared/sync.vhd @@ -0,0 +1,101 @@ +------------------------------------------------------------------------------- +--! @file sync.vhd +--! @author Michael Wurm +--! @copyright 2020 Michael Wurm +--! @brief Implementation of sync. +------------------------------------------------------------------------------- + +library ieee; +use ieee.std_logic_1164.all; + +--! @brief Entity declaration of sync +--! @details +--! The sync implementation. + +entity sync is + generic ( + init_value_g : std_ulogic := '0'; + num_delays_g : natural := 2; + sig_width_g : natural := 1); + port ( + --! @name Clocks and resets + --! @{ + + --! System clock + clk_i : in std_ulogic; + --! Asynchronous reset + rst_n_i : in std_ulogic; + + --! @} + --! @name Sync signals + --! @{ + + --! Asynchronous input + async_i : in std_ulogic_vector(sig_width_g-1 downto 0); + --! Synchronous output + sync_o : out std_ulogic_vector(sig_width_g-1 downto 0)); + + --! @} + +end entity sync; + +--! RTL implementation of sync +architecture rtl of sync is + ----------------------------------------------------------------------------- + --! @name Types and Constants + ----------------------------------------------------------------------------- + --! @{ + + type delay_t is array(num_delays_g-1 downto 0) of + std_ulogic_vector(sig_width_g-1 downto 0); + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Registers + ----------------------------------------------------------------------------- + --! @{ + + signal delay : delay_t := (others => (others => init_value_g)); + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Wires + ----------------------------------------------------------------------------- + --! @{ + + signal next_delay : delay_t := (others => (others => init_value_g)); + + --! @} + +begin -- architecture rtl + + ------------------------------------------------------------------------------ + -- Outputs + ------------------------------------------------------------------------------ + + sync_o <= delay(delay'high); + + ----------------------------------------------------------------------------- + -- Signal Assignments + ----------------------------------------------------------------------------- + + next_delay <= delay(delay'high-1 downto delay'low) & async_i; + + ------------------------------------------------------------------------------ + -- Registers + ------------------------------------------------------------------------------ + + regs : process(clk_i, rst_n_i) + procedure reset is + begin + delay <= (others => (others => init_value_g)); + end procedure reset; + begin -- process regs + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + delay <= next_delay; + end if; + end process regs; + +end architecture rtl; diff --git a/hdl/components/infrared/sync_single.vhd b/hdl/components/infrared/sync_single.vhd new file mode 100644 index 0000000..f3e76d5 --- /dev/null +++ b/hdl/components/infrared/sync_single.vhd @@ -0,0 +1,91 @@ +------------------------------------------------------------------------------- +--! @file sync_single.vhd +--! @author Michael Wurm +--! @copyright 2020 Michael Wurm +--! @brief Implementation of sync_single. +------------------------------------------------------------------------------- + +library ieee; +use ieee.std_logic_1164.all; + +--! @brief Entity declaration of sync_single +--! @details +--! The sync_single implementation. + +entity sync_single is + generic ( + init_value_g : std_ulogic := '0'; + num_delays_g : natural := 2); + port ( + --! @name Clocks and resets + --! @{ + + --! System clock + clk_i : in std_ulogic; + --! Asynchronous reset + rst_n_i : in std_ulogic; + + --! @} + --! @name Sync signals + --! @{ + + --! Asynchronous input + async_i : in std_ulogic; + --! Synchronous output + sync_o : out std_ulogic); + + --! @} + +end entity sync_single; + +--! RTL implementation of sync_single +architecture rtl of sync_single is + ----------------------------------------------------------------------------- + --! @name Internal Registers + ----------------------------------------------------------------------------- + --! @{ + + signal delay : std_ulogic_vector(num_delays_g-1 downto 0) := (others => '0'); + + --! @} + ----------------------------------------------------------------------------- + --! @name Internal Wires + ----------------------------------------------------------------------------- + --! @{ + + signal next_delay : std_ulogic_vector(delay'range); + + --! @} + +begin -- architecture rtl + + ------------------------------------------------------------------------------ + -- Outputs + ------------------------------------------------------------------------------ + + sync_o <= delay(delay'high); + + ----------------------------------------------------------------------------- + -- Signal Assignments + ----------------------------------------------------------------------------- + + next_delay <= delay(delay'high-1 downto delay'low) & async_i; + + ------------------------------------------------------------------------------ + -- Registers + ------------------------------------------------------------------------------ + + regs : process(clk_i, rst_n_i) + procedure reset is + begin + delay <= (others => init_value_g); + end procedure reset; + begin -- process regs + if rst_n_i = '0' then + reset; + elsif rising_edge(clk_i) then + delay <= next_delay; + end if; + end process regs; + +end architecture rtl; diff --git a/hdl/components/infrared/tb_infrared.vhd b/hdl/components/infrared/tb_infrared.vhd new file mode 100644 index 0000000..84d5d59 --- /dev/null +++ b/hdl/components/infrared/tb_infrared.vhd @@ -0,0 +1,127 @@ + +library IEEE; +use IEEE.std_logic_1164.all; +use IEEE.numeric_std.all; + +-- 0 -> upper 16 bit: humidity, lower 16 bit: temperature +-- 1 -> lower word of timestamp +-- 2 -> upper word of timestamp + +entity tb_infrared is +end entity tb_infrared; + +architecture bhv of tb_infrared is + + signal avs_s0_address : std_logic_vector(10 downto 0) := (others => '0'); -- avs_s0.address + signal avs_s0_read : std_logic := '0'; -- .read + signal avs_s0_readdata : std_logic_vector(31 downto 0); -- .readdata + signal avs_s0_write : std_logic := '0'; -- .write + signal avs_s0_writedata : std_logic_vector(31 downto 0) := (others => '0'); -- .writedata + signal clk : std_logic := '0'; -- clock.clk + signal nRst : std_logic := '0'; -- + signal ir_rx : std_logic := '0'; -- + signal ir_tx : std_logic; + signal irq : std_logic; + signal ir_rx_mirror : std_logic; + + constant clk_cycle_duration_c : time := 1 sec / 50E6; -- 50 MHz + constant reset_duration_c : time := 20 * clk_cycle_duration_c; + +begin -- architecture bhv + + nRst <= '1' after reset_duration_c; + clk <= not clk after clk_cycle_duration_c / 2; + + DUT : entity work.infrared + port map ( + clk_i => clk, + rst_n_i => nRst, + avs_s0_address => avs_s0_address, + avs_s0_read => avs_s0_read, + avs_s0_readdata => avs_s0_readdata, + avs_s0_write => avs_s0_write, + avs_s0_writedata => avs_s0_writedata, + ir_rx_i => ir_rx, + ir_tx_o => ir_tx, + done_recording_irq_o => irq, + ir_rx_o => ir_rx_mirror); + + test_proc : process + begin + wait for reset_duration_c + 5 ns; + + test_run_record : for test_nr in 0 to 1 loop + -- Default sensor value (idle) + ir_rx <= '1'; + wait for 200 * clk_cycle_duration_c; + + -- Generate infrared input signal + ir_rx_input_1st : for i in 0 to 10 loop + ir_rx <= not ir_rx; + wait for 10 * clk_cycle_duration_c; + end loop ir_rx_input_1st; + + -- Default sensor value (idle) + ir_rx <= '1'; + + -- Wait for interrupt generation (end of recieved IR sequence) + wait until irq = '1'; + report "(MWURM) IRQ occured (end of received IR sequence)." severity note; + wait for 10 * clk_cycle_duration_c; + + -- Read data (RAM) + read_ram_data : for i in 0 to 255 loop + avs_s0_address <= std_logic_vector(to_unsigned(i, avs_s0_address'length)); + avs_s0_read <= '1'; + + wait until clk <= '1'; + wait until clk <= '0'; + wait until clk <= '1'; + wait until clk <= '0'; + end loop read_ram_data; + + wait for 20 * clk_cycle_duration_c; + + -- Read data (control and status registers) + read_ctrl_status_data : for i in 256 to 261 loop + avs_s0_address <= std_logic_vector(to_unsigned(i, avs_s0_address'length)); + avs_s0_read <= '1'; + + wait until clk <= '1'; + wait until clk <= '0'; + wait until clk <= '1'; + wait until clk <= '0'; + end loop read_ctrl_status_data; + + wait for 200 * clk_cycle_duration_c; + end loop test_run_record; + + test_run_replay : for test_nr in 0 to 0 loop + -- Write data into replay RAM + write_ram_data : for i in 0 to 10 loop + avs_s0_address <= std_logic_vector(to_unsigned(i, avs_s0_address'length)); + avs_s0_writedata <= std_logic_vector(to_unsigned(i*10, avs_s0_writedata'length)); + avs_s0_write <= '1'; + + wait until clk <= '1'; + wait until clk <= '0'; + wait until clk <= '1'; + wait until clk <= '0'; + end loop write_ram_data; + + wait for 50 * clk_cycle_duration_c; + + avs_s0_address <= std_logic_vector(to_unsigned(256, avs_s0_address'length)); + avs_s0_writedata <= std_logic_vector(to_unsigned(1, avs_s0_writedata'length)); + avs_s0_write <= '1'; + + wait for 20 * clk_cycle_duration_c; + + end loop test_run_replay; + + avs_s0_write <= '0'; + + wait; + end process test_proc; + +end architecture bhv; diff --git a/hdl/components/infrared/wave.do b/hdl/components/infrared/wave.do new file mode 100644 index 0000000..29e3e0c --- /dev/null +++ b/hdl/components/infrared/wave.do @@ -0,0 +1,97 @@ +onerror {resume} +quietly WaveActivateNextPane {} 0 +add wave -noupdate -radix decimal /tb_infrared/avs_s0_address +add wave -noupdate /tb_infrared/avs_s0_read +add wave -noupdate -radix hexadecimal /tb_infrared/avs_s0_readdata +add wave -noupdate /tb_infrared/avs_s0_write +add wave -noupdate /tb_infrared/avs_s0_writedata +add wave -noupdate /tb_infrared/clk +add wave -noupdate /tb_infrared/nRst +add wave -noupdate /tb_infrared/ir_rx +add wave -noupdate /tb_infrared/ir_tx +add wave -noupdate -color Magenta /tb_infrared/irq +add wave -noupdate /tb_infrared/ir_rx_mirror +add wave -noupdate -divider stop_counter +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/clk_i +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/rst_n_i +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/enable_i +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/overflow_o +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/count_o +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/count +add wave -noupdate /tb_infrared/DUT/stop_counter_inst/overflow +add wave -noupdate -divider DUT +add wave -noupdate /tb_infrared/DUT/clk_i +add wave -noupdate /tb_infrared/DUT/rst_n_i +add wave -noupdate -radix decimal /tb_infrared/DUT/avs_s0_address +add wave -noupdate -radix decimal /tb_infrared/DUT/ram_addr +add wave -noupdate -radix decimal /tb_infrared/DUT/ctrl_addr +add wave -noupdate /tb_infrared/DUT/ctrl_access +add wave -noupdate /tb_infrared/DUT/avs_s0_read +add wave -noupdate -radix decimal /tb_infrared/DUT/avs_s0_readdata +add wave -noupdate /tb_infrared/DUT/avs_s0_write +add wave -noupdate -radix decimal /tb_infrared/DUT/avs_s0_writedata +add wave -noupdate /tb_infrared/DUT/ir_rx_i +add wave -noupdate /tb_infrared/DUT/ir_tx_o +add wave -noupdate /tb_infrared/DUT/done_recording_irq_o +add wave -noupdate /tb_infrared/DUT/ir_rx_o +add wave -noupdate -radix decimal /tb_infrared/DUT/ram_readdata +add wave -noupdate -radix hexadecimal /tb_infrared/DUT/ctrl_readdata +add wave -noupdate -expand -subitemconfig {/tb_infrared/DUT/ir_rx(1) {-color Magenta -height 16}} /tb_infrared/DUT/ir_rx +add wave -noupdate /tb_infrared/DUT/store_timestamp +add wave -noupdate /tb_infrared/DUT/irq_active +add wave -noupdate /tb_infrared/DUT/irq_reset +add wave -noupdate /tb_infrared/DUT/ir_rx_sync +add wave -noupdate /tb_infrared/DUT/next_ir_rx +add wave -noupdate /tb_infrared/DUT/rising +add wave -noupdate /tb_infrared/DUT/falling +add wave -noupdate /tb_infrared/DUT/recording_stopped +add wave -noupdate -radix decimal /tb_infrared/DUT/timestamp +add wave -noupdate /tb_infrared/DUT/end_of_sequence +add wave -noupdate -radix decimal -childformat {{/tb_infrared/DUT/ram_data(0) -radix decimal} {/tb_infrared/DUT/ram_data(1) -radix decimal} {/tb_infrared/DUT/ram_data(2) -radix decimal} {/tb_infrared/DUT/ram_data(3) -radix decimal} {/tb_infrared/DUT/ram_data(4) -radix decimal} {/tb_infrared/DUT/ram_data(5) -radix decimal} {/tb_infrared/DUT/ram_data(6) -radix decimal} {/tb_infrared/DUT/ram_data(7) -radix decimal} {/tb_infrared/DUT/ram_data(8) -radix decimal} {/tb_infrared/DUT/ram_data(9) -radix decimal} {/tb_infrared/DUT/ram_data(10) -radix decimal} {/tb_infrared/DUT/ram_data(11) -radix decimal} {/tb_infrared/DUT/ram_data(12) -radix decimal} {/tb_infrared/DUT/ram_data(13) -radix decimal} {/tb_infrared/DUT/ram_data(14) -radix decimal} {/tb_infrared/DUT/ram_data(15) -radix decimal} {/tb_infrared/DUT/ram_data(16) -radix decimal} {/tb_infrared/DUT/ram_data(17) -radix decimal} {/tb_infrared/DUT/ram_data(18) -radix decimal} {/tb_infrared/DUT/ram_data(19) -radix decimal} {/tb_infrared/DUT/ram_data(20) -radix decimal} {/tb_infrared/DUT/ram_data(21) -radix decimal} {/tb_infrared/DUT/ram_data(22) -radix decimal} {/tb_infrared/DUT/ram_data(23) -radix decimal} {/tb_infrared/DUT/ram_data(24) -radix decimal} {/tb_infrared/DUT/ram_data(25) -radix decimal} {/tb_infrared/DUT/ram_data(26) -radix decimal} {/tb_infrared/DUT/ram_data(27) -radix decimal} {/tb_infrared/DUT/ram_data(28) -radix decimal} {/tb_infrared/DUT/ram_data(29) -radix decimal} {/tb_infrared/DUT/ram_data(30) -radix decimal} {/tb_infrared/DUT/ram_data(31) -radix decimal} {/tb_infrared/DUT/ram_data(32) -radix decimal} {/tb_infrared/DUT/ram_data(33) -radix decimal} {/tb_infrared/DUT/ram_data(34) -radix decimal} {/tb_infrared/DUT/ram_data(35) -radix decimal} {/tb_infrared/DUT/ram_data(36) -radix decimal} {/tb_infrared/DUT/ram_data(37) -radix decimal} {/tb_infrared/DUT/ram_data(38) -radix decimal} {/tb_infrared/DUT/ram_data(39) -radix decimal} {/tb_infrared/DUT/ram_data(40) -radix decimal} {/tb_infrared/DUT/ram_data(41) -radix decimal} {/tb_infrared/DUT/ram_data(42) -radix decimal} {/tb_infrared/DUT/ram_data(43) -radix decimal} {/tb_infrared/DUT/ram_data(44) -radix decimal} {/tb_infrared/DUT/ram_data(45) -radix decimal} {/tb_infrared/DUT/ram_data(46) -radix decimal} {/tb_infrared/DUT/ram_data(47) -radix decimal} {/tb_infrared/DUT/ram_data(48) -radix decimal} {/tb_infrared/DUT/ram_data(49) -radix decimal} {/tb_infrared/DUT/ram_data(50) -radix decimal} {/tb_infrared/DUT/ram_data(51) -radix decimal} {/tb_infrared/DUT/ram_data(52) -radix decimal} {/tb_infrared/DUT/ram_data(53) -radix decimal} {/tb_infrared/DUT/ram_data(54) -radix decimal} {/tb_infrared/DUT/ram_data(55) -radix decimal} {/tb_infrared/DUT/ram_data(56) -radix decimal} {/tb_infrared/DUT/ram_data(57) -radix decimal} {/tb_infrared/DUT/ram_data(58) -radix decimal} {/tb_infrared/DUT/ram_data(59) -radix decimal} {/tb_infrared/DUT/ram_data(60) -radix decimal} {/tb_infrared/DUT/ram_data(61) -radix decimal} {/tb_infrared/DUT/ram_data(62) -radix decimal} {/tb_infrared/DUT/ram_data(63) -radix decimal} {/tb_infrared/DUT/ram_data(64) -radix decimal} {/tb_infrared/DUT/ram_data(65) -radix decimal} {/tb_infrared/DUT/ram_data(66) -radix decimal} {/tb_infrared/DUT/ram_data(67) -radix decimal} {/tb_infrared/DUT/ram_data(68) -radix decimal} {/tb_infrared/DUT/ram_data(69) -radix decimal} {/tb_infrared/DUT/ram_data(70) -radix decimal} {/tb_infrared/DUT/ram_data(71) -radix decimal} {/tb_infrared/DUT/ram_data(72) -radix decimal} {/tb_infrared/DUT/ram_data(73) -radix decimal} {/tb_infrared/DUT/ram_data(74) -radix decimal} {/tb_infrared/DUT/ram_data(75) -radix decimal} {/tb_infrared/DUT/ram_data(76) -radix decimal} {/tb_infrared/DUT/ram_data(77) -radix decimal} {/tb_infrared/DUT/ram_data(78) -radix decimal} {/tb_infrared/DUT/ram_data(79) -radix decimal} {/tb_infrared/DUT/ram_data(80) -radix decimal} {/tb_infrared/DUT/ram_data(81) -radix decimal} {/tb_infrared/DUT/ram_data(82) -radix decimal} {/tb_infrared/DUT/ram_data(83) -radix decimal} {/tb_infrared/DUT/ram_data(84) -radix decimal} {/tb_infrared/DUT/ram_data(85) -radix decimal} {/tb_infrared/DUT/ram_data(86) -radix decimal} {/tb_infrared/DUT/ram_data(87) -radix decimal} {/tb_infrared/DUT/ram_data(88) -radix decimal} {/tb_infrared/DUT/ram_data(89) -radix decimal} {/tb_infrared/DUT/ram_data(90) -radix decimal} {/tb_infrared/DUT/ram_data(91) -radix decimal} {/tb_infrared/DUT/ram_data(92) -radix decimal} {/tb_infrared/DUT/ram_data(93) -radix decimal} {/tb_infrared/DUT/ram_data(94) -radix decimal} {/tb_infrared/DUT/ram_data(95) -radix decimal} {/tb_infrared/DUT/ram_data(96) -radix decimal} {/tb_infrared/DUT/ram_data(97) -radix decimal} {/tb_infrared/DUT/ram_data(98) -radix decimal} {/tb_infrared/DUT/ram_data(99) -radix decimal} {/tb_infrared/DUT/ram_data(100) -radix decimal} {/tb_infrared/DUT/ram_data(101) -radix decimal} {/tb_infrared/DUT/ram_data(102) -radix decimal} {/tb_infrared/DUT/ram_data(103) -radix decimal} {/tb_infrared/DUT/ram_data(104) -radix decimal} {/tb_infrared/DUT/ram_data(105) -radix decimal} {/tb_infrared/DUT/ram_data(106) -radix decimal} {/tb_infrared/DUT/ram_data(107) -radix decimal} {/tb_infrared/DUT/ram_data(108) -radix decimal} {/tb_infrared/DUT/ram_data(109) -radix decimal} {/tb_infrared/DUT/ram_data(110) -radix decimal} {/tb_infrared/DUT/ram_data(111) -radix decimal} {/tb_infrared/DUT/ram_data(112) -radix decimal} {/tb_infrared/DUT/ram_data(113) -radix decimal} {/tb_infrared/DUT/ram_data(114) -radix decimal} {/tb_infrared/DUT/ram_data(115) -radix decimal} {/tb_infrared/DUT/ram_data(116) -radix decimal} {/tb_infrared/DUT/ram_data(117) -radix decimal} {/tb_infrared/DUT/ram_data(118) -radix decimal} {/tb_infrared/DUT/ram_data(119) -radix decimal} {/tb_infrared/DUT/ram_data(120) -radix decimal} {/tb_infrared/DUT/ram_data(121) -radix decimal} {/tb_infrared/DUT/ram_data(122) -radix decimal} {/tb_infrared/DUT/ram_data(123) -radix decimal} {/tb_infrared/DUT/ram_data(124) -radix decimal} {/tb_infrared/DUT/ram_data(125) -radix decimal} {/tb_infrared/DUT/ram_data(126) -radix decimal} {/tb_infrared/DUT/ram_data(127) -radix decimal} {/tb_infrared/DUT/ram_data(128) -radix decimal} {/tb_infrared/DUT/ram_data(129) -radix decimal} {/tb_infrared/DUT/ram_data(130) -radix decimal} {/tb_infrared/DUT/ram_data(131) -radix decimal} {/tb_infrared/DUT/ram_data(132) -radix decimal} {/tb_infrared/DUT/ram_data(133) -radix decimal} {/tb_infrared/DUT/ram_data(134) -radix decimal} {/tb_infrared/DUT/ram_data(135) -radix decimal} {/tb_infrared/DUT/ram_data(136) -radix decimal} {/tb_infrared/DUT/ram_data(137) -radix decimal} {/tb_infrared/DUT/ram_data(138) -radix decimal} {/tb_infrared/DUT/ram_data(139) -radix decimal} {/tb_infrared/DUT/ram_data(140) -radix decimal} {/tb_infrared/DUT/ram_data(141) -radix decimal} {/tb_infrared/DUT/ram_data(142) -radix decimal} {/tb_infrared/DUT/ram_data(143) -radix decimal} {/tb_infrared/DUT/ram_data(144) -radix decimal} {/tb_infrared/DUT/ram_data(145) -radix decimal} {/tb_infrared/DUT/ram_data(146) -radix decimal} {/tb_infrared/DUT/ram_data(147) -radix decimal} {/tb_infrared/DUT/ram_data(148) -radix decimal} {/tb_infrared/DUT/ram_data(149) -radix decimal} {/tb_infrared/DUT/ram_data(150) -radix decimal} {/tb_infrared/DUT/ram_data(151) -radix decimal} {/tb_infrared/DUT/ram_data(152) -radix decimal} {/tb_infrared/DUT/ram_data(153) -radix decimal} {/tb_infrared/DUT/ram_data(154) -radix decimal} {/tb_infrared/DUT/ram_data(155) -radix decimal} {/tb_infrared/DUT/ram_data(156) -radix decimal} {/tb_infrared/DUT/ram_data(157) -radix decimal} {/tb_infrared/DUT/ram_data(158) -radix decimal} {/tb_infrared/DUT/ram_data(159) -radix decimal} {/tb_infrared/DUT/ram_data(160) -radix decimal} {/tb_infrared/DUT/ram_data(161) -radix decimal} {/tb_infrared/DUT/ram_data(162) -radix decimal} {/tb_infrared/DUT/ram_data(163) -radix decimal} {/tb_infrared/DUT/ram_data(164) -radix decimal} {/tb_infrared/DUT/ram_data(165) -radix decimal} {/tb_infrared/DUT/ram_data(166) -radix decimal} {/tb_infrared/DUT/ram_data(167) -radix decimal} {/tb_infrared/DUT/ram_data(168) -radix decimal} {/tb_infrared/DUT/ram_data(169) -radix decimal} {/tb_infrared/DUT/ram_data(170) -radix decimal} {/tb_infrared/DUT/ram_data(171) -radix decimal} {/tb_infrared/DUT/ram_data(172) -radix decimal} {/tb_infrared/DUT/ram_data(173) -radix decimal} {/tb_infrared/DUT/ram_data(174) -radix decimal} {/tb_infrared/DUT/ram_data(175) -radix decimal} {/tb_infrared/DUT/ram_data(176) -radix decimal} {/tb_infrared/DUT/ram_data(177) -radix decimal} {/tb_infrared/DUT/ram_data(178) -radix decimal} {/tb_infrared/DUT/ram_data(179) -radix decimal} {/tb_infrared/DUT/ram_data(180) -radix decimal} {/tb_infrared/DUT/ram_data(181) -radix decimal} {/tb_infrared/DUT/ram_data(182) -radix decimal} {/tb_infrared/DUT/ram_data(183) -radix decimal} {/tb_infrared/DUT/ram_data(184) -radix decimal} {/tb_infrared/DUT/ram_data(185) -radix decimal} {/tb_infrared/DUT/ram_data(186) -radix decimal} {/tb_infrared/DUT/ram_data(187) -radix decimal} {/tb_infrared/DUT/ram_data(188) -radix decimal} {/tb_infrared/DUT/ram_data(189) -radix decimal} {/tb_infrared/DUT/ram_data(190) -radix decimal} {/tb_infrared/DUT/ram_data(191) -radix decimal} {/tb_infrared/DUT/ram_data(192) -radix decimal} {/tb_infrared/DUT/ram_data(193) -radix decimal} {/tb_infrared/DUT/ram_data(194) -radix decimal} {/tb_infrared/DUT/ram_data(195) -radix decimal} {/tb_infrared/DUT/ram_data(196) -radix decimal} {/tb_infrared/DUT/ram_data(197) -radix decimal} {/tb_infrared/DUT/ram_data(198) -radix decimal} {/tb_infrared/DUT/ram_data(199) -radix decimal} {/tb_infrared/DUT/ram_data(200) -radix decimal} {/tb_infrared/DUT/ram_data(201) -radix decimal} {/tb_infrared/DUT/ram_data(202) -radix decimal} {/tb_infrared/DUT/ram_data(203) -radix decimal} {/tb_infrared/DUT/ram_data(204) -radix decimal} {/tb_infrared/DUT/ram_data(205) -radix decimal} {/tb_infrared/DUT/ram_data(206) -radix decimal} {/tb_infrared/DUT/ram_data(207) -radix decimal} {/tb_infrared/DUT/ram_data(208) -radix decimal} {/tb_infrared/DUT/ram_data(209) -radix decimal} {/tb_infrared/DUT/ram_data(210) -radix decimal} {/tb_infrared/DUT/ram_data(211) -radix decimal} {/tb_infrared/DUT/ram_data(212) -radix decimal} {/tb_infrared/DUT/ram_data(213) -radix decimal} {/tb_infrared/DUT/ram_data(214) -radix decimal} {/tb_infrared/DUT/ram_data(215) -radix decimal} {/tb_infrared/DUT/ram_data(216) -radix decimal} {/tb_infrared/DUT/ram_data(217) -radix decimal} {/tb_infrared/DUT/ram_data(218) -radix decimal} {/tb_infrared/DUT/ram_data(219) -radix decimal} {/tb_infrared/DUT/ram_data(220) -radix decimal} {/tb_infrared/DUT/ram_data(221) -radix decimal} {/tb_infrared/DUT/ram_data(222) -radix decimal} {/tb_infrared/DUT/ram_data(223) -radix decimal} {/tb_infrared/DUT/ram_data(224) -radix decimal} {/tb_infrared/DUT/ram_data(225) -radix decimal} {/tb_infrared/DUT/ram_data(226) -radix decimal} {/tb_infrared/DUT/ram_data(227) -radix decimal} {/tb_infrared/DUT/ram_data(228) -radix decimal} {/tb_infrared/DUT/ram_data(229) -radix decimal} {/tb_infrared/DUT/ram_data(230) -radix decimal} {/tb_infrared/DUT/ram_data(231) -radix decimal} {/tb_infrared/DUT/ram_data(232) -radix decimal} {/tb_infrared/DUT/ram_data(233) -radix decimal} {/tb_infrared/DUT/ram_data(234) -radix decimal} {/tb_infrared/DUT/ram_data(235) -radix decimal} {/tb_infrared/DUT/ram_data(236) -radix decimal} {/tb_infrared/DUT/ram_data(237) -radix decimal} {/tb_infrared/DUT/ram_data(238) -radix decimal} {/tb_infrared/DUT/ram_data(239) -radix decimal} {/tb_infrared/DUT/ram_data(240) -radix decimal} {/tb_infrared/DUT/ram_data(241) -radix decimal} {/tb_infrared/DUT/ram_data(242) -radix decimal} {/tb_infrared/DUT/ram_data(243) -radix decimal} {/tb_infrared/DUT/ram_data(244) -radix decimal} {/tb_infrared/DUT/ram_data(245) -radix decimal} {/tb_infrared/DUT/ram_data(246) -radix decimal} {/tb_infrared/DUT/ram_data(247) -radix decimal} {/tb_infrared/DUT/ram_data(248) -radix decimal} {/tb_infrared/DUT/ram_data(249) -radix decimal} {/tb_infrared/DUT/ram_data(250) -radix decimal} {/tb_infrared/DUT/ram_data(251) -radix decimal} {/tb_infrared/DUT/ram_data(252) -radix decimal} {/tb_infrared/DUT/ram_data(253) -radix decimal} {/tb_infrared/DUT/ram_data(254) -radix decimal} {/tb_infrared/DUT/ram_data(255) -radix decimal}} -subitemconfig {/tb_infrared/DUT/ram_data(0) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(1) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(2) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(3) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(4) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(5) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(6) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(7) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(8) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(9) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(10) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(11) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(12) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(13) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(14) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(15) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(16) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(17) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(18) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(19) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(20) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(21) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(22) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(23) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(24) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(25) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(26) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(27) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(28) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(29) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(30) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(31) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(32) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(33) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(34) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(35) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(36) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(37) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(38) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(39) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(40) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(41) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(42) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(43) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(44) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(45) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(46) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(47) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(48) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(49) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(50) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(51) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(52) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(53) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(54) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(55) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(56) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(57) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(58) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(59) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(60) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(61) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(62) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(63) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(64) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(65) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(66) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(67) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(68) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(69) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(70) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(71) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(72) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(73) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(74) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(75) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(76) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(77) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(78) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(79) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(80) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(81) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(82) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(83) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(84) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(85) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(86) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(87) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(88) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(89) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(90) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(91) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(92) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(93) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(94) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(95) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(96) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(97) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(98) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(99) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(100) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(101) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(102) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(103) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(104) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(105) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(106) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(107) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(108) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(109) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(110) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(111) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(112) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(113) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(114) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(115) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(116) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(117) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(118) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(119) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(120) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(121) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(122) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(123) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(124) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(125) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(126) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(127) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(128) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(129) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(130) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(131) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(132) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(133) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(134) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(135) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(136) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(137) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(138) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(139) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(140) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(141) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(142) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(143) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(144) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(145) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(146) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(147) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(148) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(149) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(150) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(151) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(152) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(153) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(154) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(155) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(156) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(157) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(158) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(159) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(160) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(161) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(162) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(163) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(164) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(165) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(166) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(167) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(168) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(169) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(170) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(171) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(172) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(173) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(174) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(175) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(176) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(177) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(178) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(179) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(180) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(181) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(182) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(183) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(184) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(185) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(186) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(187) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(188) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(189) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(190) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(191) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(192) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(193) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(194) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(195) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(196) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(197) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(198) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(199) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(200) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(201) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(202) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(203) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(204) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(205) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(206) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(207) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(208) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(209) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(210) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(211) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(212) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(213) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(214) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(215) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(216) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(217) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(218) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(219) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(220) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(221) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(222) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(223) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(224) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(225) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(226) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(227) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(228) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(229) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(230) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(231) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(232) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(233) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(234) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(235) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(236) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(237) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(238) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(239) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(240) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(241) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(242) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(243) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(244) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(245) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(246) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(247) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(248) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(249) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(250) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(251) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(252) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(253) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(254) {-height 16 -radix decimal} /tb_infrared/DUT/ram_data(255) {-height 16 -radix decimal}} /tb_infrared/DUT/ram_data +add wave -noupdate -divider timestamp_counter +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/clk_i +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/rst_n_i +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/enable_i +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/overflow_o +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/count_o +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/count +add wave -noupdate /tb_infrared/DUT/timestamp_counter_inst/overflow +add wave -noupdate -divider Sender +add wave -noupdate /tb_infrared/DUT/sender_inst/clk_i +add wave -noupdate /tb_infrared/DUT/sender_inst/rst_n_i +add wave -noupdate -radix decimal /tb_infrared/DUT/sender_inst/avs_s0_address +add wave -noupdate /tb_infrared/DUT/sender_inst/avs_s0_read +add wave -noupdate /tb_infrared/DUT/sender_inst/avs_s0_readdata +add wave -noupdate /tb_infrared/DUT/sender_inst/avs_s0_write +add wave -noupdate -radix decimal /tb_infrared/DUT/sender_inst/avs_s0_writedata +add wave -noupdate /tb_infrared/DUT/sender_inst/ir_tx_o +add wave -noupdate /tb_infrared/DUT/sender_inst/done_replay_o +add wave -noupdate /tb_infrared/DUT/sender_inst/replay_running_o +add wave -noupdate -radix decimal -childformat {{/tb_infrared/DUT/sender_inst/ram_readdata(31) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(30) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(29) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(28) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(27) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(26) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(25) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(24) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(23) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(22) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(21) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(20) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(19) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(18) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(17) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(16) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(15) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(14) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(13) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(12) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(11) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(10) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(9) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(8) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(7) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(6) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(5) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(4) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(3) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(2) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(1) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_readdata(0) -radix decimal}} -subitemconfig {/tb_infrared/DUT/sender_inst/ram_readdata(31) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(30) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(29) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(28) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(27) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(26) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(25) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(24) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(23) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(22) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(21) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(20) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(19) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(18) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(17) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(16) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(15) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(14) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(13) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(12) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(11) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(10) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(9) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(8) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(7) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(6) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(5) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(4) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(3) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(2) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(1) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_readdata(0) {-height 16 -radix decimal}} /tb_infrared/DUT/sender_inst/ram_readdata +add wave -noupdate -radix decimal /tb_infrared/DUT/sender_inst/ram_addr +add wave -noupdate /tb_infrared/DUT/sender_inst/start_replay +add wave -noupdate /tb_infrared/DUT/sender_inst/replay_done +add wave -noupdate /tb_infrared/DUT/sender_inst/replay_running +add wave -noupdate /tb_infrared/DUT/sender_inst/ir_tx +add wave -noupdate /tb_infrared/DUT/sender_inst/timestamp +add wave -noupdate /tb_infrared/DUT/sender_inst/end_of_sequence +add wave -noupdate /tb_infrared/DUT/sender_inst/timestamp_match +add wave -noupdate -radix decimal -childformat {{/tb_infrared/DUT/sender_inst/ram_data(0) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(1) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(2) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(3) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(4) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(5) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(6) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(7) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(8) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(9) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(10) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(11) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(12) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(13) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(14) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(15) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(16) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(17) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(18) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(19) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(20) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(21) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(22) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(23) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(24) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(25) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(26) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(27) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(28) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(29) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(30) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(31) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(32) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(33) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(34) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(35) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(36) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(37) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(38) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(39) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(40) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(41) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(42) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(43) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(44) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(45) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(46) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(47) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(48) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(49) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(50) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(51) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(52) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(53) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(54) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(55) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(56) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(57) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(58) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(59) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(60) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(61) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(62) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(63) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(64) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(65) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(66) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(67) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(68) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(69) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(70) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(71) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(72) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(73) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(74) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(75) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(76) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(77) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(78) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(79) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(80) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(81) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(82) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(83) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(84) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(85) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(86) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(87) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(88) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(89) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(90) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(91) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(92) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(93) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(94) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(95) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(96) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(97) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(98) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(99) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(100) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(101) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(102) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(103) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(104) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(105) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(106) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(107) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(108) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(109) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(110) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(111) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(112) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(113) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(114) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(115) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(116) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(117) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(118) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(119) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(120) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(121) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(122) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(123) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(124) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(125) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(126) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(127) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(128) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(129) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(130) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(131) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(132) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(133) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(134) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(135) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(136) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(137) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(138) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(139) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(140) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(141) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(142) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(143) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(144) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(145) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(146) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(147) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(148) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(149) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(150) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(151) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(152) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(153) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(154) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(155) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(156) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(157) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(158) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(159) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(160) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(161) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(162) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(163) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(164) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(165) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(166) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(167) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(168) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(169) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(170) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(171) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(172) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(173) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(174) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(175) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(176) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(177) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(178) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(179) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(180) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(181) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(182) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(183) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(184) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(185) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(186) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(187) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(188) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(189) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(190) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(191) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(192) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(193) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(194) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(195) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(196) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(197) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(198) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(199) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(200) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(201) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(202) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(203) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(204) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(205) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(206) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(207) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(208) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(209) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(210) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(211) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(212) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(213) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(214) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(215) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(216) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(217) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(218) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(219) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(220) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(221) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(222) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(223) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(224) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(225) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(226) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(227) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(228) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(229) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(230) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(231) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(232) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(233) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(234) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(235) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(236) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(237) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(238) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(239) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(240) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(241) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(242) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(243) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(244) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(245) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(246) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(247) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(248) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(249) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(250) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(251) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(252) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(253) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(254) -radix decimal} {/tb_infrared/DUT/sender_inst/ram_data(255) -radix decimal}} -expand -subitemconfig {/tb_infrared/DUT/sender_inst/ram_data(0) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(1) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(2) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(3) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(4) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(5) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(6) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(7) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(8) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(9) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(10) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(11) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(12) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(13) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(14) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(15) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(16) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(17) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(18) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(19) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(20) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(21) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(22) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(23) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(24) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(25) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(26) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(27) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(28) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(29) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(30) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(31) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(32) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(33) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(34) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(35) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(36) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(37) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(38) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(39) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(40) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(41) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(42) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(43) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(44) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(45) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(46) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(47) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(48) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(49) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(50) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(51) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(52) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(53) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(54) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(55) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(56) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(57) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(58) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(59) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(60) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(61) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(62) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(63) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(64) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(65) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(66) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(67) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(68) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(69) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(70) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(71) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(72) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(73) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(74) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(75) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(76) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(77) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(78) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(79) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(80) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(81) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(82) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(83) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(84) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(85) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(86) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(87) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(88) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(89) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(90) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(91) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(92) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(93) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(94) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(95) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(96) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(97) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(98) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(99) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(100) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(101) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(102) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(103) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(104) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(105) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(106) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(107) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(108) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(109) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(110) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(111) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(112) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(113) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(114) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(115) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(116) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(117) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(118) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(119) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(120) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(121) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(122) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(123) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(124) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(125) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(126) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(127) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(128) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(129) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(130) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(131) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(132) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(133) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(134) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(135) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(136) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(137) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(138) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(139) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(140) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(141) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(142) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(143) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(144) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(145) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(146) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(147) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(148) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(149) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(150) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(151) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(152) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(153) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(154) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(155) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(156) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(157) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(158) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(159) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(160) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(161) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(162) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(163) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(164) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(165) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(166) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(167) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(168) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(169) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(170) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(171) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(172) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(173) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(174) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(175) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(176) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(177) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(178) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(179) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(180) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(181) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(182) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(183) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(184) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(185) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(186) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(187) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(188) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(189) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(190) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(191) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(192) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(193) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(194) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(195) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(196) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(197) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(198) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(199) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(200) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(201) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(202) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(203) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(204) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(205) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(206) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(207) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(208) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(209) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(210) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(211) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(212) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(213) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(214) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(215) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(216) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(217) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(218) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(219) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(220) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(221) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(222) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(223) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(224) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(225) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(226) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(227) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(228) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(229) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(230) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(231) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(232) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(233) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(234) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(235) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(236) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(237) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(238) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(239) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(240) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(241) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(242) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(243) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(244) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(245) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(246) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(247) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(248) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(249) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(250) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(251) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(252) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(253) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(254) {-height 16 -radix decimal} /tb_infrared/DUT/sender_inst/ram_data(255) {-height 16 -radix decimal}} /tb_infrared/DUT/sender_inst/ram_data +TreeUpdate [SetDefaultTree] +WaveRestoreCursors {{Cursor 1} {84120000 ps} 0} {{Cursor 2} {1955587 ps} 0} +quietly wave cursor active 1 +configure wave -namecolwidth 324 +configure wave -valuecolwidth 164 +configure wave -justifyvalue left +configure wave -signalnamewidth 0 +configure wave -snapdistance 10 +configure wave -datasetprefix 0 +configure wave -rowmargin 4 +configure wave -childrowmargin 2 +configure wave -gridoffset 0 +configure wave -gridperiod 1 +configure wave -griddelta 40 +configure wave -timeline 0 +configure wave -timelineunits ns +update +WaveRestoreZoom {25187302 ps} {103937510 ps} diff --git a/hdl/ip/subsystemHMI.qsys b/hdl/ip/subsystemHMI.qsys index 2f0333a..bcdf834 100644 --- a/hdl/ip/subsystemHMI.qsys +++ b/hdl/ip/subsystemHMI.qsys @@ -9,6 +9,14 @@ categories="System" /> + + + + + + + + - + + @@ -219,45 +260,45 @@ version="1.0" enabled="1"> - + - + - $${FILENAME}_subsystemApds9301 + subsystemHMI_subsystemApds9301 - + - + - $${FILENAME}_subsystemHdc1000 + subsystemHMI_subsystemHdc1000 - + - + - $${FILENAME}_subsystemMpu9250 + subsystemHMI_subsystemMpu9250 - + diff --git a/hdl/top.vhd b/hdl/top.vhd index e8b54f5..98848be 100644 --- a/hdl/top.vhd +++ b/hdl/top.vhd @@ -1,399 +1,412 @@ -library ieee; -use ieee.std_logic_1164.all; -use ieee.numeric_std.all; - -ENTITY top IS - -PORT( - ---------FPGA Connections------------- - CLOCK_50 : in std_logic; - SW : in std_logic_vector(9 downto 0); - LEDR : out std_logic_vector(9 downto 0); - - - -- //////////// SEG7 ////////// - HEX0 : out std_logic_vector(6 downto 0); - HEX1 : out std_logic_vector(6 downto 0); - HEX2 : out std_logic_vector(6 downto 0); - HEX3 : out std_logic_vector(6 downto 0); - HEX4 : out std_logic_vector(6 downto 0); - HEX5 : out std_logic_vector(6 downto 0); - - - ---------HPS Connections--------------- - HPS_CONV_USB_N : inout std_logic; - HPS_DDR3_ADDR : out std_logic_vector(14 downto 0); - HPS_DDR3_BA : out std_logic_vector(2 downto 0); - HPS_DDR3_CAS_N : out std_logic; - HPS_DDR3_CKE : out std_logic; - HPS_DDR3_CK_N : out std_logic; - HPS_DDR3_CK_P : out std_logic; - HPS_DDR3_CS_N : out std_logic; - HPS_DDR3_DM : out std_logic_vector(3 downto 0); - HPS_DDR3_DQ : inout std_logic_vector(31 downto 0); - HPS_DDR3_DQS_N : inout std_logic_vector(3 downto 0); - HPS_DDR3_DQS_P : inout std_logic_vector(3 downto 0); - HPS_DDR3_ODT : out std_logic; - HPS_DDR3_RAS_N : out std_logic; - HPS_DDR3_RESET_N : out std_logic; - HPS_DDR3_RZQ : in std_logic; - HPS_DDR3_WE_N : out std_logic; - - HPS_ENET_GTX_CLK : out std_logic; - HPS_ENET_INT_N : inout std_logic; - HPS_ENET_MDC : out std_logic; - HPS_ENET_MDIO : inout std_logic; - HPS_ENET_RX_CLK : in std_logic; - HPS_ENET_RX_DATA : in std_logic_vector(3 downto 0); - HPS_ENET_RX_DV : in std_logic; - HPS_ENET_TX_DATA : out std_logic_vector(3 downto 0); - HPS_ENET_TX_EN : out std_logic; - - HPS_KEY : inout std_logic; - HPS_LED : inout std_logic; - - HPS_SD_CLK : out std_logic; - HPS_SD_CMD : inout std_logic; - HPS_SD_DATA : inout std_logic_vector(3 downto 0); - - HPS_UART_RX : in std_logic; - HPS_UART_TX : out std_logic; - - HPS_USB_CLKOUT : in std_logic; - HPS_USB_DATA : inout std_logic_vector(7 downto 0); - HPS_USB_DIR : in std_logic; - HPS_USB_NXT : in std_logic; - HPS_USB_STP : out std_logic; - - HPS_I2C1_SCLK : inout std_logic; - HPS_I2C1_SDAT : inout std_logic; - HPS_I2C2_SCLK : inout std_logic; - HPS_I2C2_SDAT : inout std_logic; - HPS_I2C_CONTROL : inout std_logic; - - HPS_LTC_GPIO : inout std_logic; - HPS_GSENSOR_INT : inout std_logic; - - HPS_SPIM_CLK : out std_logic; - HPS_SPIM_MISO : in std_logic; - HPS_SPIM_MOSI : out std_logic; - HPS_SPIM_SS : inout std_logic; - - --////////// GPIO, GPIO connect to RFS - RF and Sensor ////////// - --BT_KEY : inout std_logic; - --BT_UART_RX : in std_logic; - --BT_UART_TX : out std_logic; - LSENSOR_INT : in std_logic; - LSENSOR_SCL : inout std_logic; - LSENSOR_SDA : inout std_logic; - MPU_AD0_SDO : in std_logic; - MPU_CS_n : inout std_logic; - MPU_FSYNC : out std_logic; - MPU_INT : in std_logic; - MPU_SCL_SCLK : inout std_logic; - MPU_SDA_SDI : inout std_logic; - RH_TEMP_DRDY_n : in std_ulogic; - RH_TEMP_I2C_SCL : inout std_logic; - RH_TEMP_I2C_SDA : inout std_logic; - TMD_D : out std_logic_vector(7 downto 0); - --UART2USB_CTS : in std_logic; - --UART2USB_RTS : out std_logic; - --UART2USB_RX : in std_logic; - --UART2USB_TX : out std_logic; - --WIFI_EN : out std_logic; - --WIFI_RST_n : out std_logic; - --WIFI_UART0_CTS : in std_logic; - --WIFI_UART0_RTS : out std_logic; - --WIFI_UART0_RX : in std_logic; - --WIFI_UART0_TX : out std_logic; - --WIFI_UART1_RX : in std_logic - GPIO_0 : out std_logic_vector(35 downto 0) -); - -END ENTITY; - -ARCHITECTURE MAIN OF top IS - component HPSPlatform is - port ( - clk_clk : in std_logic := 'X'; -- clk - hps_0_h2f_reset_reset_n : out std_logic; -- reset_n - hps_0_f2h_cold_reset_req_reset_n : in std_logic := 'X'; -- reset_n - hps_0_f2h_debug_reset_req_reset_n : in std_logic := 'X'; -- reset_n - hps_0_f2h_stm_hw_events_stm_hwevents : in std_logic_vector(27 downto 0) := (others => 'X'); -- stm_hwevents - hps_0_f2h_warm_reset_req_reset_n : in std_logic := 'X'; -- reset_n - hps_io_hps_io_emac1_inst_TX_CLK : out std_logic; -- hps_io_emac1_inst_TX_CLK - hps_io_hps_io_emac1_inst_TXD0 : out std_logic; -- hps_io_emac1_inst_TXD0 - hps_io_hps_io_emac1_inst_TXD1 : out std_logic; -- hps_io_emac1_inst_TXD1 - hps_io_hps_io_emac1_inst_TXD2 : out std_logic; -- hps_io_emac1_inst_TXD2 - hps_io_hps_io_emac1_inst_TXD3 : out std_logic; -- hps_io_emac1_inst_TXD3 - hps_io_hps_io_emac1_inst_RXD0 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD0 - hps_io_hps_io_emac1_inst_MDIO : inout std_logic := 'X'; -- hps_io_emac1_inst_MDIO - hps_io_hps_io_emac1_inst_MDC : out std_logic; -- hps_io_emac1_inst_MDC - hps_io_hps_io_emac1_inst_RX_CTL : in std_logic := 'X'; -- hps_io_emac1_inst_RX_CTL - hps_io_hps_io_emac1_inst_TX_CTL : out std_logic; -- hps_io_emac1_inst_TX_CTL - hps_io_hps_io_emac1_inst_RX_CLK : in std_logic := 'X'; -- hps_io_emac1_inst_RX_CLK - hps_io_hps_io_emac1_inst_RXD1 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD1 - hps_io_hps_io_emac1_inst_RXD2 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD2 - hps_io_hps_io_emac1_inst_RXD3 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD3 - hps_io_hps_io_sdio_inst_CMD : inout std_logic := 'X'; -- hps_io_sdio_inst_CMD - hps_io_hps_io_sdio_inst_D0 : inout std_logic := 'X'; -- hps_io_sdio_inst_D0 - hps_io_hps_io_sdio_inst_D1 : inout std_logic := 'X'; -- hps_io_sdio_inst_D1 - hps_io_hps_io_sdio_inst_CLK : out std_logic; -- hps_io_sdio_inst_CLK - hps_io_hps_io_sdio_inst_D2 : inout std_logic := 'X'; -- hps_io_sdio_inst_D2 - hps_io_hps_io_sdio_inst_D3 : inout std_logic := 'X'; -- hps_io_sdio_inst_D3 - hps_io_hps_io_usb1_inst_D0 : inout std_logic := 'X'; -- hps_io_usb1_inst_D0 - hps_io_hps_io_usb1_inst_D1 : inout std_logic := 'X'; -- hps_io_usb1_inst_D1 - hps_io_hps_io_usb1_inst_D2 : inout std_logic := 'X'; -- hps_io_usb1_inst_D2 - hps_io_hps_io_usb1_inst_D3 : inout std_logic := 'X'; -- hps_io_usb1_inst_D3 - hps_io_hps_io_usb1_inst_D4 : inout std_logic := 'X'; -- hps_io_usb1_inst_D4 - hps_io_hps_io_usb1_inst_D5 : inout std_logic := 'X'; -- hps_io_usb1_inst_D5 - hps_io_hps_io_usb1_inst_D6 : inout std_logic := 'X'; -- hps_io_usb1_inst_D6 - hps_io_hps_io_usb1_inst_D7 : inout std_logic := 'X'; -- hps_io_usb1_inst_D7 - hps_io_hps_io_usb1_inst_CLK : in std_logic := 'X'; -- hps_io_usb1_inst_CLK - hps_io_hps_io_usb1_inst_STP : out std_logic; -- hps_io_usb1_inst_STP - hps_io_hps_io_usb1_inst_DIR : in std_logic := 'X'; -- hps_io_usb1_inst_DIR - hps_io_hps_io_usb1_inst_NXT : in std_logic := 'X'; -- hps_io_usb1_inst_NXT - hps_io_hps_io_spim1_inst_CLK : out std_logic; -- hps_io_spim1_inst_CLK - hps_io_hps_io_spim1_inst_MOSI : out std_logic; -- hps_io_spim1_inst_MOSI - hps_io_hps_io_spim1_inst_MISO : in std_logic := 'X'; -- hps_io_spim1_inst_MISO - hps_io_hps_io_spim1_inst_SS0 : out std_logic; -- hps_io_spim1_inst_SS0 - hps_io_hps_io_uart0_inst_RX : in std_logic := 'X'; -- hps_io_uart0_inst_RX - hps_io_hps_io_uart0_inst_TX : out std_logic; -- hps_io_uart0_inst_TX - hps_io_hps_io_i2c0_inst_SDA : inout std_logic := 'X'; -- hps_io_i2c0_inst_SDA - hps_io_hps_io_i2c0_inst_SCL : inout std_logic := 'X'; -- hps_io_i2c0_inst_SCL - hps_io_hps_io_i2c1_inst_SDA : inout std_logic := 'X'; -- hps_io_i2c1_inst_SDA - hps_io_hps_io_i2c1_inst_SCL : inout std_logic := 'X'; -- hps_io_i2c1_inst_SCL - hps_io_hps_io_gpio_inst_GPIO09 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO09 - hps_io_hps_io_gpio_inst_GPIO35 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO35 - hps_io_hps_io_gpio_inst_GPIO40 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO40 - hps_io_hps_io_gpio_inst_GPIO48 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO48 - hps_io_hps_io_gpio_inst_GPIO53 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO53 - hps_io_hps_io_gpio_inst_GPIO54 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO54 - hps_io_hps_io_gpio_inst_GPIO61 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO61 - memory_mem_a : out std_logic_vector(14 downto 0); -- mem_a - memory_mem_ba : out std_logic_vector(2 downto 0); -- mem_ba - memory_mem_ck : out std_logic; -- mem_ck - memory_mem_ck_n : out std_logic; -- mem_ck_n - memory_mem_cke : out std_logic; -- mem_cke - memory_mem_cs_n : out std_logic; -- mem_cs_n - memory_mem_ras_n : out std_logic; -- mem_ras_n - memory_mem_cas_n : out std_logic; -- mem_cas_n - memory_mem_we_n : out std_logic; -- mem_we_n - memory_mem_reset_n : out std_logic; -- mem_reset_n - memory_mem_dq : inout std_logic_vector(31 downto 0) := (others => 'X'); -- mem_dq - memory_mem_dqs : inout std_logic_vector(3 downto 0) := (others => 'X'); -- mem_dqs - memory_mem_dqs_n : inout std_logic_vector(3 downto 0) := (others => 'X'); -- mem_dqs_n - memory_mem_odt : out std_logic; -- mem_odt - memory_mem_dm : out std_logic_vector(3 downto 0); -- mem_dm - memory_oct_rzqin : in std_logic := 'X'; -- oct_rzqin - reset_reset_n : in std_logic := 'X'; -- reset_n - leds_external_connection_export : out std_logic_vector(9 downto 0); -- export - seven_segment_conduit_end_export : out std_logic_vector(41 downto 0); -- export - switches_external_connection_export : in std_logic_vector(9 downto 0) := (others => 'X'); -- export - hmi_subsystemapds9301_apdsinterrupt_irq_n : in std_logic := 'X'; -- irq_n - hmi_subsystemapds9301_i2c_scl_in : in std_logic := 'X'; -- scl_in - hmi_subsystemapds9301_i2c_scl_oe : out std_logic; -- scl_oe - hmi_subsystemapds9301_i2c_sda_in : in std_logic := 'X'; -- sda_in - hmi_subsystemapds9301_i2c_sda_oe : out std_logic; -- sda_oe - hmi_subsystemhdc1000_hdcrdy_interrupt : in std_logic := 'X'; -- interrupt - hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_in : in std_logic := 'X'; -- sda_in - hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_in : in std_logic := 'X'; -- scl_in - hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_oe : out std_logic; -- sda_oe - hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_oe : out std_logic; -- scl_oe - hmi_subsystemmpu9250_spi_MISO : in std_logic := 'X'; -- MISO - hmi_subsystemmpu9250_spi_MOSI : out std_logic; -- MOSI - hmi_subsystemmpu9250_spi_SCLK : out std_logic; -- SCLK - hmi_subsystemmpu9250_spi_SS_n : out std_logic; -- SS_n - hmi_subsystemmpu9250_mpuint_irq_n : in std_logic := 'X' -- irq_n - ); - end component HPSPlatform; - - component i2c_io_buf - PORT - ( - datain : IN STD_LOGIC_VECTOR (1 DOWNTO 0); - oe : IN STD_LOGIC_VECTOR (1 DOWNTO 0); - dataio : INOUT STD_LOGIC_VECTOR (1 DOWNTO 0); - dataout : OUT STD_LOGIC_VECTOR (1 DOWNTO 0) - ); - end component; - - - signal HPS_H2F_RST : std_logic; - - constant hps_cold_reset : std_logic := '0'; - constant hps_warm_reset : std_logic := '0'; - constant hps_debug_reset : std_logic := '0'; - constant sync_levels : natural := 100; - - signal stm_hw_events : std_logic_vector(27 downto 0); - signal test : std_logic; - signal key_reset_sync : std_logic_vector(sync_levels downto 0); - - signal hdc1000_i2c_serial_sda_in : std_logic; - signal hdc1000_i2c_serial_scl_in : std_logic; - signal hdc1000_i2c_serial_sda_oe : std_logic; - signal hdc1000_i2c_serial_scl_oe : std_logic; - - signal apds9301_i2c_serial_sda_in : std_logic; - signal apds9301_i2c_serial_scl_in : std_logic; - signal apds9301_i2c_serial_sda_oe : std_logic; - signal apds9301_i2c_serial_scl_oe : std_logic; - -BEGIN - - -u0 : component HPSPlatform - port map ( - clk_clk => CLOCK_50, -- clk.clk - reset_reset_n => key_reset_sync(0), -- reset.reset_n - memory_mem_a => HPS_DDR3_ADDR, -- memory.mem_a - memory_mem_ba => HPS_DDR3_BA, -- .mem_ba - memory_mem_ck => HPS_DDR3_CK_P, -- .mem_ck - memory_mem_ck_n => HPS_DDR3_CK_N, -- .mem_ck_n - memory_mem_cke => HPS_DDR3_CKE, -- .mem_cke - memory_mem_cs_n => HPS_DDR3_CS_N, -- .mem_cs_n - memory_mem_ras_n => HPS_DDR3_RAS_N, -- .mem_ras_n - memory_mem_cas_n => HPS_DDR3_CAS_N, -- .mem_cas_n - memory_mem_we_n => HPS_DDR3_WE_N, -- .mem_we_n - memory_mem_reset_n => HPS_DDR3_RESET_N, -- .mem_reset_n - memory_mem_dq => HPS_DDR3_DQ, -- .mem_dq - memory_mem_dqs => HPS_DDR3_DQS_P, -- .mem_dqs - memory_mem_dqs_n => HPS_DDR3_DQS_N, -- .mem_dqs_n - memory_mem_odt => HPS_DDR3_ODT, -- .mem_odt - memory_mem_dm => HPS_DDR3_DM, -- .mem_dm - memory_oct_rzqin => HPS_DDR3_RZQ, -- .oct_rzqin - hps_0_h2f_reset_reset_n => HPS_H2F_RST, -- hps_0_h2f_reset.reset_n - hps_0_f2h_cold_reset_req_reset_n => not(hps_cold_reset), -- hps_0_f2h_cold_reset_req.reset_n - hps_0_f2h_debug_reset_req_reset_n => not(hps_debug_reset), -- hps_0_f2h_debug_reset_req.reset_n - hps_0_f2h_stm_hw_events_stm_hwevents => stm_hw_events, -- hps_0_f2h_stm_hw_events.stm_hwevents - hps_0_f2h_warm_reset_req_reset_n => not(hps_warm_reset), -- hps_0_f2h_warm_reset_req.reset_n - hps_io_hps_io_emac1_inst_TX_CLK => HPS_ENET_GTX_CLK, -- hps_io.hps_io_emac1_inst_TX_CLK - hps_io_hps_io_emac1_inst_TXD0 => HPS_ENET_TX_DATA(0), -- .hps_io_emac1_inst_TXD0 - hps_io_hps_io_emac1_inst_TXD1 => HPS_ENET_TX_DATA(1), -- .hps_io_emac1_inst_TXD1 - hps_io_hps_io_emac1_inst_TXD2 => HPS_ENET_TX_DATA(2), -- .hps_io_emac1_inst_TXD2 - hps_io_hps_io_emac1_inst_TXD3 => HPS_ENET_TX_DATA(3), -- .hps_io_emac1_inst_TXD3 - hps_io_hps_io_emac1_inst_RXD0 => HPS_ENET_RX_DATA(0), -- .hps_io_emac1_inst_RXD0 - hps_io_hps_io_emac1_inst_MDIO => HPS_ENET_MDIO, -- .hps_io_emac1_inst_MDIO - hps_io_hps_io_emac1_inst_MDC => HPS_ENET_MDC, -- .hps_io_emac1_inst_MDC - hps_io_hps_io_emac1_inst_RX_CTL => HPS_ENET_RX_DV, -- .hps_io_emac1_inst_RX_CTL - hps_io_hps_io_emac1_inst_TX_CTL => HPS_ENET_TX_EN, -- .hps_io_emac1_inst_TX_CTL - hps_io_hps_io_emac1_inst_RX_CLK => HPS_ENET_RX_CLK, -- .hps_io_emac1_inst_RX_CLK - hps_io_hps_io_emac1_inst_RXD1 => HPS_ENET_RX_DATA(1), -- .hps_io_emac1_inst_RXD1 - hps_io_hps_io_emac1_inst_RXD2 => HPS_ENET_RX_DATA(2), -- .hps_io_emac1_inst_RXD2 - hps_io_hps_io_emac1_inst_RXD3 => HPS_ENET_RX_DATA(3), -- .hps_io_emac1_inst_RXD3 - hps_io_hps_io_sdio_inst_CMD => HPS_SD_CMD, -- .hps_io_sdio_inst_CMD - hps_io_hps_io_sdio_inst_D0 => HPS_SD_DATA(0), -- .hps_io_sdio_inst_D0 - hps_io_hps_io_sdio_inst_D1 => HPS_SD_DATA(1), -- .hps_io_sdio_inst_D1 - hps_io_hps_io_sdio_inst_CLK => HPS_SD_CLK, -- .hps_io_sdio_inst_CLK - hps_io_hps_io_sdio_inst_D2 => HPS_SD_DATA(2), -- .hps_io_sdio_inst_D2 - hps_io_hps_io_sdio_inst_D3 => HPS_SD_DATA(3), -- .hps_io_sdio_inst_D3 - hps_io_hps_io_usb1_inst_D0 => HPS_USB_DATA(0), -- .hps_io_usb1_inst_D0 - hps_io_hps_io_usb1_inst_D1 => HPS_USB_DATA(1), -- .hps_io_usb1_inst_D1 - hps_io_hps_io_usb1_inst_D2 => HPS_USB_DATA(2), -- .hps_io_usb1_inst_D2 - hps_io_hps_io_usb1_inst_D3 => HPS_USB_DATA(3), -- .hps_io_usb1_inst_D3 - hps_io_hps_io_usb1_inst_D4 => HPS_USB_DATA(4), -- .hps_io_usb1_inst_D4 - hps_io_hps_io_usb1_inst_D5 => HPS_USB_DATA(5), -- .hps_io_usb1_inst_D5 - hps_io_hps_io_usb1_inst_D6 => HPS_USB_DATA(6), -- .hps_io_usb1_inst_D6 - hps_io_hps_io_usb1_inst_D7 => HPS_USB_DATA(7), -- .hps_io_usb1_inst_D7 - hps_io_hps_io_usb1_inst_CLK => HPS_USB_CLKOUT, -- .hps_io_usb1_inst_CLK - hps_io_hps_io_usb1_inst_STP => HPS_USB_STP, -- .hps_io_usb1_inst_STP - hps_io_hps_io_usb1_inst_DIR => HPS_USB_DIR, -- .hps_io_usb1_inst_DIR - hps_io_hps_io_usb1_inst_NXT => HPS_USB_NXT, -- .hps_io_usb1_inst_NXT - hps_io_hps_io_spim1_inst_CLK => HPS_SPIM_CLK, -- .hps_io_spim1_inst_CLK - hps_io_hps_io_spim1_inst_MOSI => HPS_SPIM_MOSI, -- .hps_io_spim1_inst_MOSI - hps_io_hps_io_spim1_inst_MISO => HPS_SPIM_MISO, -- .hps_io_spim1_inst_MISO - hps_io_hps_io_spim1_inst_SS0 => HPS_SPIM_SS, -- .hps_io_spim1_inst_SS0 - hps_io_hps_io_uart0_inst_RX => HPS_UART_RX, -- .hps_io_uart0_inst_RX - hps_io_hps_io_uart0_inst_TX => HPS_UART_TX, -- .hps_io_uart0_inst_TX - hps_io_hps_io_i2c0_inst_SDA => HPS_I2C1_SDAT, -- .hps_io_i2c0_inst_SDA - hps_io_hps_io_i2c0_inst_SCL => HPS_I2C1_SCLK, -- .hps_io_i2c0_inst_SCL - hps_io_hps_io_i2c1_inst_SDA => HPS_I2C2_SDAT, -- .hps_io_i2c1_inst_SDA - hps_io_hps_io_i2c1_inst_SCL => HPS_I2C2_SCLK, -- .hps_io_i2c1_inst_SCL - hps_io_hps_io_gpio_inst_GPIO09 => HPS_CONV_USB_N, -- hps_io_gpio_inst_GPIO09 - hps_io_hps_io_gpio_inst_GPIO35 => HPS_ENET_INT_N, -- .hps_io_gpio_inst_GPIO35 - hps_io_hps_io_gpio_inst_GPIO40 => HPS_LTC_GPIO, -- .hps_io_gpio_inst_GPIO40 - hps_io_hps_io_gpio_inst_GPIO48 => HPS_I2C_CONTROL, -- .hps_io_gpio_inst_GPIO48 - hps_io_hps_io_gpio_inst_GPIO53 => HPS_LED, -- hps_io_gpio_inst_GPIO53 - hps_io_hps_io_gpio_inst_GPIO54 => HPS_KEY, -- hps_io_gpio_inst_GPIO54 - hps_io_hps_io_gpio_inst_GPIO61 => HPS_GSENSOR_INT, -- .hps_io_gpio_inst_GPIO61 - - - -- periph --- leds_external_connection_export => LEDR, -- led_external_connection.export - switches_external_connection_export => SW, -- sw_external_connection.export - - seven_segment_conduit_end_export(6+7*0 downto 7*0) => HEX0, - seven_segment_conduit_end_export(6+7*1 downto 7*1) => HEX1, - seven_segment_conduit_end_export(6+7*2 downto 7*2) => HEX2, - seven_segment_conduit_end_export(6+7*3 downto 7*3) => HEX3, - seven_segment_conduit_end_export(6+7*4 downto 7*4) => HEX4, - seven_segment_conduit_end_export(6+7*5 downto 7*5) => HEX5, - - hmi_subsystemhdc1000_hdcrdy_interrupt => RH_TEMP_DRDY_n, -- hdc1000_0_hdcrdy.interrupt - hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_in => hdc1000_i2c_serial_sda_in, -- hdc1000_i2c_0_i2c_serial.sda_in - hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_in => hdc1000_i2c_serial_scl_in, -- .scl_in - hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_oe => hdc1000_i2c_serial_sda_oe, -- .sda_oe - hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_oe => hdc1000_i2c_serial_scl_oe, -- .scl_oe - - hmi_subsystemapds9301_apdsinterrupt_irq_n => LSENSOR_INT, -- hmi_subsystemapds9301_apdsinterrupt.irq_n - hmi_subsystemapds9301_i2c_sda_in => apds9301_i2c_serial_sda_in, -- hmi_subsystemapds9301_i2c_0_i2c_serial.scl_in - hmi_subsystemapds9301_i2c_scl_in => apds9301_i2c_serial_scl_in, -- .scl_oe - hmi_subsystemapds9301_i2c_sda_oe => apds9301_i2c_serial_sda_oe, -- .sda_in - hmi_subsystemapds9301_i2c_scl_oe => apds9301_i2c_serial_scl_oe, - - hmi_subsystemmpu9250_spi_MISO => MPU_AD0_SDO, -- hmi_subsystemmpu9250_spi_0_external.MISO - hmi_subsystemmpu9250_spi_MOSI => MPU_SDA_SDI, -- .MOSI - hmi_subsystemmpu9250_spi_SCLK => MPU_SCL_SCLK, -- .SCLK - hmi_subsystemmpu9250_spi_SS_n => MPU_CS_n, -- .SS_n - hmi_subsystemmpu9250_mpuint_irq_n => MPU_INT -- hmi_subsystemmpu9250_mpuint.irq_n - ); - - key_sync : process( CLOCK_50, HPS_H2F_RST, SW(0) ) - begin - if (HPS_H2F_RST AND SW(0)) = '0' then - key_reset_sync <= (others => '0'); - elsif rising_edge(CLOCK_50) then - key_reset_sync(sync_levels) <= '1'; - key_reset_sync(sync_levels-1 downto 0) <= key_reset_sync(sync_levels downto 1); - end if; - end process; -- key_sync - - hdc1000_i2c_io : component i2c_io_buf - port map ( - datain => (others => '0'), - oe(1) => hdc1000_i2c_serial_scl_oe, - oe(0) => hdc1000_i2c_serial_sda_oe, - dataout(1) => hdc1000_i2c_serial_scl_in, - dataout(0) => hdc1000_i2c_serial_sda_in, - dataio(1) => RH_TEMP_I2C_SCL, - dataio(0) => RH_TEMP_I2C_SDA); - - apds9301_i2c_io : component i2c_io_buf - port map ( - datain => (others => '0'), - oe(1) => apds9301_i2c_serial_scl_oe, - oe(0) => apds9301_i2c_serial_sda_oe, - dataout(1) => apds9301_i2c_serial_scl_in, - dataout(0) => apds9301_i2c_serial_sda_in, - dataio(1) => LSENSOR_SCL, - dataio(0) => LSENSOR_SDA); - - LEDR(0) <= HPS_H2F_RST AND key_reset_sync(0); - LEDR(LEDR'high downto 1) <= (others => '0'); - - GPIO_0( 0) <= RH_TEMP_DRDY_n; - GPIO_0( 1) <= RH_TEMP_I2C_SCL; - GPIO_0( 2) <= RH_TEMP_I2C_SDA; - - GPIO_0( 4) <= LSENSOR_INT; - GPIO_0( 5) <= LSENSOR_SCL; - GPIO_0( 6) <= LSENSOR_SDA; - - GPIO_0(10) <= MPU_SCL_SCLK; - GPIO_0(11) <= MPU_CS_n; - GPIO_0(12) <= MPU_INT; - GPIO_0(14) <= MPU_AD0_SDO; - GPIO_0(15) <= MPU_SDA_SDI; - -END ARCHITECTURE; +library ieee; +use ieee.std_logic_1164.all; +use ieee.numeric_std.all; + +ENTITY top IS + +PORT( + ---------FPGA Connections------------- + CLOCK_50 : in std_logic; + SW : in std_logic_vector(9 downto 0); + LEDR : out std_logic_vector(9 downto 0); + + + -- //////////// SEG7 ////////// + HEX0 : out std_logic_vector(6 downto 0); + HEX1 : out std_logic_vector(6 downto 0); + HEX2 : out std_logic_vector(6 downto 0); + HEX3 : out std_logic_vector(6 downto 0); + HEX4 : out std_logic_vector(6 downto 0); + HEX5 : out std_logic_vector(6 downto 0); + + -- //////////// Infrared Interface ////////// + IRDA_RXD : in std_logic; + IRDA_TXD : out std_logic; + + ---------HPS Connections--------------- + HPS_CONV_USB_N : inout std_logic; + HPS_DDR3_ADDR : out std_logic_vector(14 downto 0); + HPS_DDR3_BA : out std_logic_vector(2 downto 0); + HPS_DDR3_CAS_N : out std_logic; + HPS_DDR3_CKE : out std_logic; + HPS_DDR3_CK_N : out std_logic; + HPS_DDR3_CK_P : out std_logic; + HPS_DDR3_CS_N : out std_logic; + HPS_DDR3_DM : out std_logic_vector(3 downto 0); + HPS_DDR3_DQ : inout std_logic_vector(31 downto 0); + HPS_DDR3_DQS_N : inout std_logic_vector(3 downto 0); + HPS_DDR3_DQS_P : inout std_logic_vector(3 downto 0); + HPS_DDR3_ODT : out std_logic; + HPS_DDR3_RAS_N : out std_logic; + HPS_DDR3_RESET_N : out std_logic; + HPS_DDR3_RZQ : in std_logic; + HPS_DDR3_WE_N : out std_logic; + + HPS_ENET_GTX_CLK : out std_logic; + HPS_ENET_INT_N : inout std_logic; + HPS_ENET_MDC : out std_logic; + HPS_ENET_MDIO : inout std_logic; + HPS_ENET_RX_CLK : in std_logic; + HPS_ENET_RX_DATA : in std_logic_vector(3 downto 0); + HPS_ENET_RX_DV : in std_logic; + HPS_ENET_TX_DATA : out std_logic_vector(3 downto 0); + HPS_ENET_TX_EN : out std_logic; + + HPS_KEY : inout std_logic; + HPS_LED : inout std_logic; + + HPS_SD_CLK : out std_logic; + HPS_SD_CMD : inout std_logic; + HPS_SD_DATA : inout std_logic_vector(3 downto 0); + + HPS_UART_RX : in std_logic; + HPS_UART_TX : out std_logic; + + HPS_USB_CLKOUT : in std_logic; + HPS_USB_DATA : inout std_logic_vector(7 downto 0); + HPS_USB_DIR : in std_logic; + HPS_USB_NXT : in std_logic; + HPS_USB_STP : out std_logic; + + HPS_I2C1_SCLK : inout std_logic; + HPS_I2C1_SDAT : inout std_logic; + HPS_I2C2_SCLK : inout std_logic; + HPS_I2C2_SDAT : inout std_logic; + HPS_I2C_CONTROL : inout std_logic; + + HPS_LTC_GPIO : inout std_logic; + HPS_GSENSOR_INT : inout std_logic; + + HPS_SPIM_CLK : out std_logic; + HPS_SPIM_MISO : in std_logic; + HPS_SPIM_MOSI : out std_logic; + HPS_SPIM_SS : inout std_logic; + + --////////// GPIO, GPIO connect to RFS - RF and Sensor ////////// + --BT_KEY : inout std_logic; + --BT_UART_RX : in std_logic; + --BT_UART_TX : out std_logic; + LSENSOR_INT : in std_logic; + LSENSOR_SCL : inout std_logic; + LSENSOR_SDA : inout std_logic; + MPU_AD0_SDO : in std_logic; + MPU_CS_n : inout std_logic; + MPU_FSYNC : out std_logic; + MPU_INT : in std_logic; + MPU_SCL_SCLK : inout std_logic; + MPU_SDA_SDI : inout std_logic; + RH_TEMP_DRDY_n : in std_ulogic; + RH_TEMP_I2C_SCL : inout std_logic; + RH_TEMP_I2C_SDA : inout std_logic; + TMD_D : out std_logic_vector(7 downto 0); + --UART2USB_CTS : in std_logic; + --UART2USB_RTS : out std_logic; + --UART2USB_RX : in std_logic; + --UART2USB_TX : out std_logic; + --WIFI_EN : out std_logic; + --WIFI_RST_n : out std_logic; + --WIFI_UART0_CTS : in std_logic; + --WIFI_UART0_RTS : out std_logic; + --WIFI_UART0_RX : in std_logic; + --WIFI_UART0_TX : out std_logic; + --WIFI_UART1_RX : in std_logic + GPIO_0 : out std_logic_vector(35 downto 0) +); + +END ENTITY; + +ARCHITECTURE MAIN OF top IS + component HPSPlatform is + port ( + clk_clk : in std_logic := 'X'; -- clk + hmi_subsystemapds9301_apdsinterrupt_irq_n : in std_logic := 'X'; -- irq_n + hmi_subsystemapds9301_i2c_sda_in : in std_logic := 'X'; -- sda_in + hmi_subsystemapds9301_i2c_scl_in : in std_logic := 'X'; -- scl_in + hmi_subsystemapds9301_i2c_sda_oe : out std_logic; -- sda_oe + hmi_subsystemapds9301_i2c_scl_oe : out std_logic; -- scl_oe + hmi_subsystemhdc1000_hdcrdy_interrupt : in std_logic := 'X'; -- interrupt + hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_in : in std_logic := 'X'; -- sda_in + hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_in : in std_logic := 'X'; -- scl_in + hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_oe : out std_logic; -- sda_oe + hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_oe : out std_logic; -- scl_oe + hmi_subsystemmpu9250_mpuint_irq_n : in std_logic := 'X'; -- irq_n + hmi_subsystemmpu9250_spi_sclk : out std_logic; -- sclk + hmi_subsystemmpu9250_spi_mosi : out std_logic; -- mosi + hmi_subsystemmpu9250_spi_miso : in std_logic := 'X'; -- miso + hmi_subsystemmpu9250_spi_ss_n : out std_logic; -- ss_n + hps_0_f2h_cold_reset_req_reset_n : in std_logic := 'X'; -- reset_n + hps_0_f2h_debug_reset_req_reset_n : in std_logic := 'X'; -- reset_n + hps_0_f2h_stm_hw_events_stm_hwevents : in std_logic_vector(27 downto 0) := (others => 'X'); -- stm_hwevents + hps_0_f2h_warm_reset_req_reset_n : in std_logic := 'X'; -- reset_n + hps_0_h2f_reset_reset_n : out std_logic; -- reset_n + hps_io_hps_io_emac1_inst_TX_CLK : out std_logic; -- hps_io_emac1_inst_TX_CLK + hps_io_hps_io_emac1_inst_TXD0 : out std_logic; -- hps_io_emac1_inst_TXD0 + hps_io_hps_io_emac1_inst_TXD1 : out std_logic; -- hps_io_emac1_inst_TXD1 + hps_io_hps_io_emac1_inst_TXD2 : out std_logic; -- hps_io_emac1_inst_TXD2 + hps_io_hps_io_emac1_inst_TXD3 : out std_logic; -- hps_io_emac1_inst_TXD3 + hps_io_hps_io_emac1_inst_RXD0 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD0 + hps_io_hps_io_emac1_inst_MDIO : inout std_logic := 'X'; -- hps_io_emac1_inst_MDIO + hps_io_hps_io_emac1_inst_MDC : out std_logic; -- hps_io_emac1_inst_MDC + hps_io_hps_io_emac1_inst_RX_CTL : in std_logic := 'X'; -- hps_io_emac1_inst_RX_CTL + hps_io_hps_io_emac1_inst_TX_CTL : out std_logic; -- hps_io_emac1_inst_TX_CTL + hps_io_hps_io_emac1_inst_RX_CLK : in std_logic := 'X'; -- hps_io_emac1_inst_RX_CLK + hps_io_hps_io_emac1_inst_RXD1 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD1 + hps_io_hps_io_emac1_inst_RXD2 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD2 + hps_io_hps_io_emac1_inst_RXD3 : in std_logic := 'X'; -- hps_io_emac1_inst_RXD3 + hps_io_hps_io_sdio_inst_CMD : inout std_logic := 'X'; -- hps_io_sdio_inst_CMD + hps_io_hps_io_sdio_inst_D0 : inout std_logic := 'X'; -- hps_io_sdio_inst_D0 + hps_io_hps_io_sdio_inst_D1 : inout std_logic := 'X'; -- hps_io_sdio_inst_D1 + hps_io_hps_io_sdio_inst_CLK : out std_logic; -- hps_io_sdio_inst_CLK + hps_io_hps_io_sdio_inst_D2 : inout std_logic := 'X'; -- hps_io_sdio_inst_D2 + hps_io_hps_io_sdio_inst_D3 : inout std_logic := 'X'; -- hps_io_sdio_inst_D3 + hps_io_hps_io_usb1_inst_D0 : inout std_logic := 'X'; -- hps_io_usb1_inst_D0 + hps_io_hps_io_usb1_inst_D1 : inout std_logic := 'X'; -- hps_io_usb1_inst_D1 + hps_io_hps_io_usb1_inst_D2 : inout std_logic := 'X'; -- hps_io_usb1_inst_D2 + hps_io_hps_io_usb1_inst_D3 : inout std_logic := 'X'; -- hps_io_usb1_inst_D3 + hps_io_hps_io_usb1_inst_D4 : inout std_logic := 'X'; -- hps_io_usb1_inst_D4 + hps_io_hps_io_usb1_inst_D5 : inout std_logic := 'X'; -- hps_io_usb1_inst_D5 + hps_io_hps_io_usb1_inst_D6 : inout std_logic := 'X'; -- hps_io_usb1_inst_D6 + hps_io_hps_io_usb1_inst_D7 : inout std_logic := 'X'; -- hps_io_usb1_inst_D7 + hps_io_hps_io_usb1_inst_CLK : in std_logic := 'X'; -- hps_io_usb1_inst_CLK + hps_io_hps_io_usb1_inst_STP : out std_logic; -- hps_io_usb1_inst_STP + hps_io_hps_io_usb1_inst_DIR : in std_logic := 'X'; -- hps_io_usb1_inst_DIR + hps_io_hps_io_usb1_inst_NXT : in std_logic := 'X'; -- hps_io_usb1_inst_NXT + hps_io_hps_io_spim1_inst_CLK : out std_logic; -- hps_io_spim1_inst_CLK + hps_io_hps_io_spim1_inst_MOSI : out std_logic; -- hps_io_spim1_inst_MOSI + hps_io_hps_io_spim1_inst_MISO : in std_logic := 'X'; -- hps_io_spim1_inst_MISO + hps_io_hps_io_spim1_inst_SS0 : out std_logic; -- hps_io_spim1_inst_SS0 + hps_io_hps_io_uart0_inst_RX : in std_logic := 'X'; -- hps_io_uart0_inst_RX + hps_io_hps_io_uart0_inst_TX : out std_logic; -- hps_io_uart0_inst_TX + hps_io_hps_io_i2c0_inst_SDA : inout std_logic := 'X'; -- hps_io_i2c0_inst_SDA + hps_io_hps_io_i2c0_inst_SCL : inout std_logic := 'X'; -- hps_io_i2c0_inst_SCL + hps_io_hps_io_i2c1_inst_SDA : inout std_logic := 'X'; -- hps_io_i2c1_inst_SDA + hps_io_hps_io_i2c1_inst_SCL : inout std_logic := 'X'; -- hps_io_i2c1_inst_SCL + hps_io_hps_io_gpio_inst_GPIO09 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO09 + hps_io_hps_io_gpio_inst_GPIO35 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO35 + hps_io_hps_io_gpio_inst_GPIO40 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO40 + hps_io_hps_io_gpio_inst_GPIO48 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO48 + hps_io_hps_io_gpio_inst_GPIO53 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO53 + hps_io_hps_io_gpio_inst_GPIO54 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO54 + hps_io_hps_io_gpio_inst_GPIO61 : inout std_logic := 'X'; -- hps_io_gpio_inst_GPIO61 + leds_external_connection_export : out std_logic_vector(9 downto 0); -- export + memory_mem_a : out std_logic_vector(14 downto 0); -- mem_a + memory_mem_ba : out std_logic_vector(2 downto 0); -- mem_ba + memory_mem_ck : out std_logic; -- mem_ck + memory_mem_ck_n : out std_logic; -- mem_ck_n + memory_mem_cke : out std_logic; -- mem_cke + memory_mem_cs_n : out std_logic; -- mem_cs_n + memory_mem_ras_n : out std_logic; -- mem_ras_n + memory_mem_cas_n : out std_logic; -- mem_cas_n + memory_mem_we_n : out std_logic; -- mem_we_n + memory_mem_reset_n : out std_logic; -- mem_reset_n + memory_mem_dq : inout std_logic_vector(31 downto 0) := (others => 'X'); -- mem_dq + memory_mem_dqs : inout std_logic_vector(3 downto 0) := (others => 'X'); -- mem_dqs + memory_mem_dqs_n : inout std_logic_vector(3 downto 0) := (others => 'X'); -- mem_dqs_n + memory_mem_odt : out std_logic; -- mem_odt + memory_mem_dm : out std_logic_vector(3 downto 0); -- mem_dm + memory_oct_rzqin : in std_logic := 'X'; -- oct_rzqin + reset_reset_n : in std_logic := 'X'; -- reset_n + seven_segment_conduit_end_export : out std_logic_vector(41 downto 0); -- export + switches_external_connection_export : in std_logic_vector(9 downto 0) := (others => 'X'); -- export + hmi_infrared_ir_tx_o_conduit : out std_logic; -- conduit + hmi_infrared_ir_rx_o_conduit : out std_logic; -- conduit + hmi_infrared_ir_rx_i_conduit : in std_logic := 'X' -- conduit + ); + end component HPSPlatform; + + component i2c_io_buf + PORT + ( + datain : IN STD_LOGIC_VECTOR (1 DOWNTO 0); + oe : IN STD_LOGIC_VECTOR (1 DOWNTO 0); + dataio : INOUT STD_LOGIC_VECTOR (1 DOWNTO 0); + dataout : OUT STD_LOGIC_VECTOR (1 DOWNTO 0) + ); + end component; + + + signal HPS_H2F_RST : std_logic; + + constant hps_cold_reset : std_logic := '0'; + constant hps_warm_reset : std_logic := '0'; + constant hps_debug_reset : std_logic := '0'; + constant sync_levels : natural := 100; + + signal stm_hw_events : std_logic_vector(27 downto 0); + signal test : std_logic; + signal key_reset_sync : std_logic_vector(sync_levels downto 0); + + signal hdc1000_i2c_serial_sda_in : std_logic; + signal hdc1000_i2c_serial_scl_in : std_logic; + signal hdc1000_i2c_serial_sda_oe : std_logic; + signal hdc1000_i2c_serial_scl_oe : std_logic; + + signal apds9301_i2c_serial_sda_in : std_logic; + signal apds9301_i2c_serial_scl_in : std_logic; + signal apds9301_i2c_serial_sda_oe : std_logic; + signal apds9301_i2c_serial_scl_oe : std_logic; + + signal ir_rx_mirror : std_logic; + +BEGIN + + +u0 : component HPSPlatform + port map ( + clk_clk => CLOCK_50, -- clk.clk + reset_reset_n => key_reset_sync(0), -- reset.reset_n + memory_mem_a => HPS_DDR3_ADDR, -- memory.mem_a + memory_mem_ba => HPS_DDR3_BA, -- .mem_ba + memory_mem_ck => HPS_DDR3_CK_P, -- .mem_ck + memory_mem_ck_n => HPS_DDR3_CK_N, -- .mem_ck_n + memory_mem_cke => HPS_DDR3_CKE, -- .mem_cke + memory_mem_cs_n => HPS_DDR3_CS_N, -- .mem_cs_n + memory_mem_ras_n => HPS_DDR3_RAS_N, -- .mem_ras_n + memory_mem_cas_n => HPS_DDR3_CAS_N, -- .mem_cas_n + memory_mem_we_n => HPS_DDR3_WE_N, -- .mem_we_n + memory_mem_reset_n => HPS_DDR3_RESET_N, -- .mem_reset_n + memory_mem_dq => HPS_DDR3_DQ, -- .mem_dq + memory_mem_dqs => HPS_DDR3_DQS_P, -- .mem_dqs + memory_mem_dqs_n => HPS_DDR3_DQS_N, -- .mem_dqs_n + memory_mem_odt => HPS_DDR3_ODT, -- .mem_odt + memory_mem_dm => HPS_DDR3_DM, -- .mem_dm + memory_oct_rzqin => HPS_DDR3_RZQ, -- .oct_rzqin + hps_0_h2f_reset_reset_n => HPS_H2F_RST, -- hps_0_h2f_reset.reset_n + hps_0_f2h_cold_reset_req_reset_n => not(hps_cold_reset), -- hps_0_f2h_cold_reset_req.reset_n + hps_0_f2h_debug_reset_req_reset_n => not(hps_debug_reset), -- hps_0_f2h_debug_reset_req.reset_n + hps_0_f2h_stm_hw_events_stm_hwevents => stm_hw_events, -- hps_0_f2h_stm_hw_events.stm_hwevents + hps_0_f2h_warm_reset_req_reset_n => not(hps_warm_reset), -- hps_0_f2h_warm_reset_req.reset_n + hps_io_hps_io_emac1_inst_TX_CLK => HPS_ENET_GTX_CLK, -- hps_io.hps_io_emac1_inst_TX_CLK + hps_io_hps_io_emac1_inst_TXD0 => HPS_ENET_TX_DATA(0), -- .hps_io_emac1_inst_TXD0 + hps_io_hps_io_emac1_inst_TXD1 => HPS_ENET_TX_DATA(1), -- .hps_io_emac1_inst_TXD1 + hps_io_hps_io_emac1_inst_TXD2 => HPS_ENET_TX_DATA(2), -- .hps_io_emac1_inst_TXD2 + hps_io_hps_io_emac1_inst_TXD3 => HPS_ENET_TX_DATA(3), -- .hps_io_emac1_inst_TXD3 + hps_io_hps_io_emac1_inst_RXD0 => HPS_ENET_RX_DATA(0), -- .hps_io_emac1_inst_RXD0 + hps_io_hps_io_emac1_inst_MDIO => HPS_ENET_MDIO, -- .hps_io_emac1_inst_MDIO + hps_io_hps_io_emac1_inst_MDC => HPS_ENET_MDC, -- .hps_io_emac1_inst_MDC + hps_io_hps_io_emac1_inst_RX_CTL => HPS_ENET_RX_DV, -- .hps_io_emac1_inst_RX_CTL + hps_io_hps_io_emac1_inst_TX_CTL => HPS_ENET_TX_EN, -- .hps_io_emac1_inst_TX_CTL + hps_io_hps_io_emac1_inst_RX_CLK => HPS_ENET_RX_CLK, -- .hps_io_emac1_inst_RX_CLK + hps_io_hps_io_emac1_inst_RXD1 => HPS_ENET_RX_DATA(1), -- .hps_io_emac1_inst_RXD1 + hps_io_hps_io_emac1_inst_RXD2 => HPS_ENET_RX_DATA(2), -- .hps_io_emac1_inst_RXD2 + hps_io_hps_io_emac1_inst_RXD3 => HPS_ENET_RX_DATA(3), -- .hps_io_emac1_inst_RXD3 + hps_io_hps_io_sdio_inst_CMD => HPS_SD_CMD, -- .hps_io_sdio_inst_CMD + hps_io_hps_io_sdio_inst_D0 => HPS_SD_DATA(0), -- .hps_io_sdio_inst_D0 + hps_io_hps_io_sdio_inst_D1 => HPS_SD_DATA(1), -- .hps_io_sdio_inst_D1 + hps_io_hps_io_sdio_inst_CLK => HPS_SD_CLK, -- .hps_io_sdio_inst_CLK + hps_io_hps_io_sdio_inst_D2 => HPS_SD_DATA(2), -- .hps_io_sdio_inst_D2 + hps_io_hps_io_sdio_inst_D3 => HPS_SD_DATA(3), -- .hps_io_sdio_inst_D3 + hps_io_hps_io_usb1_inst_D0 => HPS_USB_DATA(0), -- .hps_io_usb1_inst_D0 + hps_io_hps_io_usb1_inst_D1 => HPS_USB_DATA(1), -- .hps_io_usb1_inst_D1 + hps_io_hps_io_usb1_inst_D2 => HPS_USB_DATA(2), -- .hps_io_usb1_inst_D2 + hps_io_hps_io_usb1_inst_D3 => HPS_USB_DATA(3), -- .hps_io_usb1_inst_D3 + hps_io_hps_io_usb1_inst_D4 => HPS_USB_DATA(4), -- .hps_io_usb1_inst_D4 + hps_io_hps_io_usb1_inst_D5 => HPS_USB_DATA(5), -- .hps_io_usb1_inst_D5 + hps_io_hps_io_usb1_inst_D6 => HPS_USB_DATA(6), -- .hps_io_usb1_inst_D6 + hps_io_hps_io_usb1_inst_D7 => HPS_USB_DATA(7), -- .hps_io_usb1_inst_D7 + hps_io_hps_io_usb1_inst_CLK => HPS_USB_CLKOUT, -- .hps_io_usb1_inst_CLK + hps_io_hps_io_usb1_inst_STP => HPS_USB_STP, -- .hps_io_usb1_inst_STP + hps_io_hps_io_usb1_inst_DIR => HPS_USB_DIR, -- .hps_io_usb1_inst_DIR + hps_io_hps_io_usb1_inst_NXT => HPS_USB_NXT, -- .hps_io_usb1_inst_NXT + hps_io_hps_io_spim1_inst_CLK => HPS_SPIM_CLK, -- .hps_io_spim1_inst_CLK + hps_io_hps_io_spim1_inst_MOSI => HPS_SPIM_MOSI, -- .hps_io_spim1_inst_MOSI + hps_io_hps_io_spim1_inst_MISO => HPS_SPIM_MISO, -- .hps_io_spim1_inst_MISO + hps_io_hps_io_spim1_inst_SS0 => HPS_SPIM_SS, -- .hps_io_spim1_inst_SS0 + hps_io_hps_io_uart0_inst_RX => HPS_UART_RX, -- .hps_io_uart0_inst_RX + hps_io_hps_io_uart0_inst_TX => HPS_UART_TX, -- .hps_io_uart0_inst_TX + hps_io_hps_io_i2c0_inst_SDA => HPS_I2C1_SDAT, -- .hps_io_i2c0_inst_SDA + hps_io_hps_io_i2c0_inst_SCL => HPS_I2C1_SCLK, -- .hps_io_i2c0_inst_SCL + hps_io_hps_io_i2c1_inst_SDA => HPS_I2C2_SDAT, -- .hps_io_i2c1_inst_SDA + hps_io_hps_io_i2c1_inst_SCL => HPS_I2C2_SCLK, -- .hps_io_i2c1_inst_SCL + hps_io_hps_io_gpio_inst_GPIO09 => HPS_CONV_USB_N, -- hps_io_gpio_inst_GPIO09 + hps_io_hps_io_gpio_inst_GPIO35 => HPS_ENET_INT_N, -- .hps_io_gpio_inst_GPIO35 + hps_io_hps_io_gpio_inst_GPIO40 => HPS_LTC_GPIO, -- .hps_io_gpio_inst_GPIO40 + hps_io_hps_io_gpio_inst_GPIO48 => HPS_I2C_CONTROL, -- .hps_io_gpio_inst_GPIO48 + hps_io_hps_io_gpio_inst_GPIO53 => HPS_LED, -- hps_io_gpio_inst_GPIO53 + hps_io_hps_io_gpio_inst_GPIO54 => HPS_KEY, -- hps_io_gpio_inst_GPIO54 + hps_io_hps_io_gpio_inst_GPIO61 => HPS_GSENSOR_INT, -- .hps_io_gpio_inst_GPIO61 + + + -- periph +-- leds_external_connection_export => LEDR, -- led_external_connection.export + switches_external_connection_export => SW, -- sw_external_connection.export + + seven_segment_conduit_end_export(6+7*0 downto 7*0) => HEX0, + seven_segment_conduit_end_export(6+7*1 downto 7*1) => HEX1, + seven_segment_conduit_end_export(6+7*2 downto 7*2) => HEX2, + seven_segment_conduit_end_export(6+7*3 downto 7*3) => HEX3, + seven_segment_conduit_end_export(6+7*4 downto 7*4) => HEX4, + seven_segment_conduit_end_export(6+7*5 downto 7*5) => HEX5, + + hmi_subsystemhdc1000_hdcrdy_interrupt => RH_TEMP_DRDY_n, -- hdc1000_0_hdcrdy.interrupt + hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_in => hdc1000_i2c_serial_sda_in, -- hdc1000_i2c_0_i2c_serial.sda_in + hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_in => hdc1000_i2c_serial_scl_in, -- .scl_in + hmi_subsystemhdc1000_i2c_0_i2c_serial_sda_oe => hdc1000_i2c_serial_sda_oe, -- .sda_oe + hmi_subsystemhdc1000_i2c_0_i2c_serial_scl_oe => hdc1000_i2c_serial_scl_oe, -- .scl_oe + + hmi_subsystemapds9301_apdsinterrupt_irq_n => LSENSOR_INT, -- hmi_subsystemapds9301_apdsinterrupt.irq_n + hmi_subsystemapds9301_i2c_sda_in => apds9301_i2c_serial_sda_in, -- hmi_subsystemapds9301_i2c_0_i2c_serial.scl_in + hmi_subsystemapds9301_i2c_scl_in => apds9301_i2c_serial_scl_in, -- .scl_oe + hmi_subsystemapds9301_i2c_sda_oe => apds9301_i2c_serial_sda_oe, -- .sda_in + hmi_subsystemapds9301_i2c_scl_oe => apds9301_i2c_serial_scl_oe, + + hmi_subsystemmpu9250_spi_miso => MPU_AD0_SDO, -- hmi_subsystemmpu9250_spi_0_external.MISO + hmi_subsystemmpu9250_spi_mosi => MPU_SDA_SDI, -- .MOSI + hmi_subsystemmpu9250_spi_sclk => MPU_SCL_SCLK, -- .SCLK + hmi_subsystemmpu9250_spi_ss_n => MPU_CS_n, -- .SS_n + hmi_subsystemmpu9250_mpuint_irq_n => MPU_INT, -- hmi_subsystemmpu9250_mpuint.irq_n + + hmi_infrared_ir_tx_o_conduit => IRDA_TXD, + hmi_infrared_ir_rx_o_conduit => ir_rx_mirror, + hmi_infrared_ir_rx_i_conduit => IRDA_RXD + ); + + key_sync : process( CLOCK_50, HPS_H2F_RST, SW(0) ) + begin + if (HPS_H2F_RST AND SW(0)) = '0' then + key_reset_sync <= (others => '0'); + elsif rising_edge(CLOCK_50) then + key_reset_sync(sync_levels) <= '1'; + key_reset_sync(sync_levels-1 downto 0) <= key_reset_sync(sync_levels downto 1); + end if; + end process; -- key_sync + + hdc1000_i2c_io : component i2c_io_buf + port map ( + datain => (others => '0'), + oe(1) => hdc1000_i2c_serial_scl_oe, + oe(0) => hdc1000_i2c_serial_sda_oe, + dataout(1) => hdc1000_i2c_serial_scl_in, + dataout(0) => hdc1000_i2c_serial_sda_in, + dataio(1) => RH_TEMP_I2C_SCL, + dataio(0) => RH_TEMP_I2C_SDA); + + apds9301_i2c_io : component i2c_io_buf + port map ( + datain => (others => '0'), + oe(1) => apds9301_i2c_serial_scl_oe, + oe(0) => apds9301_i2c_serial_sda_oe, + dataout(1) => apds9301_i2c_serial_scl_in, + dataout(0) => apds9301_i2c_serial_sda_in, + dataio(1) => LSENSOR_SCL, + dataio(0) => LSENSOR_SDA); + + LEDR(0) <= HPS_H2F_RST AND key_reset_sync(0); + LEDR(1) <= ir_rx_mirror; + LEDR(LEDR'high downto 2) <= (others => '0'); + + GPIO_0( 0) <= RH_TEMP_DRDY_n; + GPIO_0( 1) <= RH_TEMP_I2C_SCL; + GPIO_0( 2) <= RH_TEMP_I2C_SDA; + + GPIO_0( 4) <= LSENSOR_INT; + GPIO_0( 5) <= LSENSOR_SCL; + GPIO_0( 6) <= LSENSOR_SDA; + + GPIO_0(10) <= MPU_SCL_SCLK; + GPIO_0(11) <= MPU_CS_n; + GPIO_0(12) <= MPU_INT; + GPIO_0(14) <= MPU_AD0_SDO; + GPIO_0(15) <= MPU_SDA_SDI; + +END ARCHITECTURE; diff --git a/user/event_sensors/mpu9250.cpp b/user/event_sensors/mpu9250.cpp index ae8e8c0..98de80e 100644 --- a/user/event_sensors/mpu9250.cpp +++ b/user/event_sensors/mpu9250.cpp @@ -15,38 +15,35 @@ #include "mpu9250_conversion.txx" #include "tsu.h" - using namespace std::placeholders; - - /* Helper macro for creating the JSON string. */ -#define ADD_FIELD_IF_AVAILABLE(stream, f) \ - do { \ - if (f.has_value()) { \ - stream << "\"" #f "\":" << f.value() << ","; \ - } \ +#define ADD_FIELD_IF_AVAILABLE(stream, f) \ + do \ + { \ + if (f.has_value()) \ + { \ + stream << "\"" #f "\":" << f.value() << ","; \ + } \ } while (0) - /* IO Control (IOCTL) */ -#define IOC_MODE_POLLING 0 -#define IOC_MODE_BUFFER 1 -#define IOC_SET_PID 2 -#define IOC_SET_THRESHOLD 3 +#define IOC_MODE_POLLING 0 +#define IOC_MODE_BUFFER 1 +#define IOC_SET_PID 2 +#define IOC_SET_THRESHOLD 3 #define IOC_CMD_SET_READ_POLLING _IO(4711, IOC_MODE_POLLING) -#define IOC_CMD_SET_READ_BUFFER _IO(4711, IOC_MODE_BUFFER) +#define IOC_CMD_SET_READ_BUFFER _IO(4711, IOC_MODE_BUFFER) #define IOC_CMD_SET_PID _IO(4711, IOC_SET_PID) #define IOC_CMD_SET_THRESHOLD _IOW(4711, IOC_SET_THRESHOLD, sizeof(uint32_t)) - /* Event specific defines */ -#define EVENT_SIGNAL_NR 10 -#define EVENT_PACKETS 1024 - +#define EVENT_SIGNAL_NR 10 // (SIGUSR1) +#define EVENT_PACKETS 1024 /* Data structures used for reading the character device */ -struct MPU9250PollingPOD { +struct MPU9250PollingPOD +{ uint32_t timestamp_lo; uint32_t timestamp_hi; int16_t gyro_x; @@ -60,7 +57,8 @@ struct MPU9250PollingPOD { int16_t mag_z; } __attribute__((packed)); -struct MPU9250EventPOD { +struct MPU9250EventPOD +{ uint32_t timestamp_lo[EVENT_PACKETS]; uint32_t timestamp_hi[EVENT_PACKETS]; uint16_t acc_x[EVENT_PACKETS]; @@ -74,19 +72,17 @@ struct MPU9250EventPOD { uint16_t mag_z[EVENT_PACKETS]; } __attribute__((packed)); - /* Constants and variables used to communication with the CDEV and the main application */ static const std::string CHARACTER_DEVICE = "/dev/mpu9250"; static std::mutex mpuMutex; static std::function &&)> fSetEventQueue; - - // // Implementation of the sensor in event mode // -static void eventDataReady(int, siginfo_t *, void *) { +static void eventDataReady(int, siginfo_t *, void *) +{ #ifdef NO_SENSORS std::vector eventData; eventData.push_back({}); @@ -102,46 +98,49 @@ static void eventDataReady(int, siginfo_t *, void *) { auto _fpgaLck = lockFPGA(); std::unique_lock _mpuLck(mpuMutex); - auto fd = fopen(CHARACTER_DEVICE.c_str(), "rb"); - if (!fd) { + if (!fd) + { std::cerr << "Failed to open character device in signal handler" << std::endl; return; } // request the event buffers - if (ioctl(fileno(fd), IOC_CMD_SET_READ_BUFFER) < 0) { + if (ioctl(fileno(fd), IOC_CMD_SET_READ_BUFFER) < 0) + { std::cerr << "Requesting the event buffers failed: " << strerror(errno) << std::endl; fclose(fd); return; } - auto readSuccessful = true; - if (fread(&pod, READ_SIZE, 1, fd) != 1) { + if (fread(&pod, READ_SIZE, 1, fd) != 1) + { std::cerr << "Failed to read event data" << std::endl; readSuccessful = false; } - if (readSuccessful) { + if (readSuccessful) + { std::vector eventData; - for (int i = 0; i < EVENT_PACKETS; ++i) { + for (int i = 0; i < EVENT_PACKETS; ++i) + { MPU9250Data data = {}; MPU9250PollingPOD tmp; - tmp.acc_x = pod.acc_x[i]; - tmp.acc_y = pod.acc_y[i]; - tmp.acc_z = pod.acc_z[i]; + tmp.acc_x = pod.acc_x[i]; + tmp.acc_y = pod.acc_y[i]; + tmp.acc_z = pod.acc_z[i]; tmp.gyro_x = pod.gyro_x[i]; tmp.gyro_y = pod.gyro_y[i]; tmp.gyro_z = pod.gyro_z[i]; - tmp.mag_x = pod.mag_x[i]; - tmp.mag_y = pod.mag_y[i]; - tmp.mag_z = pod.mag_z[i]; + tmp.mag_x = pod.mag_x[i]; + tmp.mag_y = pod.mag_y[i]; + tmp.mag_z = pod.mag_z[i]; data.event = true; - data.timeStamp = (((uint64_t) pod.timestamp_hi[i]) << 32) | pod.timestamp_lo[i]; + data.timeStamp = (((uint64_t)pod.timestamp_hi[i]) << 32) | pod.timestamp_lo[i]; convertAccUnits(tmp, data); convertMagUnits(tmp, data); convertGyroUnits(tmp, data); @@ -160,9 +159,9 @@ static void eventDataReady(int, siginfo_t *, void *) { fSetEventQueue(std::move(eventData)); } - // reset the mode to polling mode - if (ioctl(fileno(fd), IOC_CMD_SET_READ_POLLING) < 0) { + if (ioctl(fileno(fd), IOC_CMD_SET_READ_POLLING) < 0) + { std::cerr << "Requesting polling mode failed: " << strerror(errno) << std::endl; std::cerr << "ATTENTION: The application invariants are broken now! An application restart is required!" << std::endl; @@ -173,35 +172,37 @@ static void eventDataReady(int, siginfo_t *, void *) { fclose(fd); } - - // // Implementation of the sensor in polling mode // -std::string MPU9250::getTopic() const { +std::string MPU9250::getTopic() const +{ static const std::string TOPIC_NAME = "compressed/sensors/mpu9250"; return TOPIC_NAME; } -MPU9250::MPU9250(double frequency, int threshold) : StreamingSensor(frequency), threshold(threshold) { +MPU9250::MPU9250(double frequency, int threshold) : StreamingSensor(frequency), threshold(threshold) +{ fSetEventQueue = std::bind(&MPU9250::setEventQueue, this, _1); - #ifndef NO_SENSORS auto fd = fopen(CHARACTER_DEVICE.c_str(), "rb"); - if (!fd) { + if (!fd) + { std::cerr << "Failed to open character device sensor constructor" << std::endl; return; } - if (ioctl(fileno(fd), IOC_CMD_SET_PID) < 0) { + if (ioctl(fileno(fd), IOC_CMD_SET_PID) < 0) + { std::cerr << "Failed to set PID: " << strerror(errno) << std::endl; fclose(fd); return; } - if (ioctl(fileno(fd), IOC_CMD_SET_THRESHOLD, &threshold) < 0) { + if (ioctl(fileno(fd), IOC_CMD_SET_THRESHOLD, &threshold) < 0) + { std::cerr << "Failed to set threshold: " << strerror(errno) << std::endl; fclose(fd); return; @@ -210,14 +211,14 @@ MPU9250::MPU9250(double frequency, int threshold) : StreamingSensor(frequency), fclose(fd); #endif - struct sigaction sig; sig.sa_sigaction = eventDataReady; - sig.sa_flags = SA_SIGINFO; + sig.sa_flags = SA_SIGINFO; sigaction(EVENT_SIGNAL_NR, &sig, NULL); } -std::optional MPU9250::doPoll() { +std::optional MPU9250::doPoll() +{ #ifdef NO_SENSORS static int c = 0; @@ -238,23 +239,23 @@ std::optional MPU9250::doPoll() { #endif static const int READ_SIZE = sizeof(MPU9250PollingPOD); - MPU9250Data results {}; - MPU9250PollingPOD pod {}; - + MPU9250Data results{}; + MPU9250PollingPOD pod{}; // lock fpga device using a lock guard // the result is never used, but it keeps the mutex locked until it goes out of scope auto _fpgaLck = lockFPGA(); std::unique_lock _mpuLck(mpuMutex); - auto fd = fopen(CHARACTER_DEVICE.c_str(), "rb"); - if (!fd) { + if (!fd) + { std::cerr << "Failed to open character device '" << CHARACTER_DEVICE << "'" << std::endl; return {}; } - if (ioctl(fileno(fd), IOC_CMD_SET_READ_POLLING) < 0) { + if (ioctl(fileno(fd), IOC_CMD_SET_READ_POLLING) < 0) + { std::cerr << "Requesting polling mode failed: " << strerror(errno) << std::endl; std::cerr << "ATTENTION: The application invariants are broken now! An application restart is required!" << std::endl; @@ -262,27 +263,26 @@ std::optional MPU9250::doPoll() { return {}; } - - if (fread(&pod, READ_SIZE, 1, fd) != 1) { + if (fread(&pod, READ_SIZE, 1, fd) != 1) + { std::cerr << "Failed to read sensor values" << std::endl; fclose(fd); return {}; } - - results.timeStamp = (((uint64_t) pod.timestamp_hi) << 32) | pod.timestamp_lo; + results.timeStamp = (((uint64_t)pod.timestamp_hi) << 32) | pod.timestamp_lo; results.event = false; convertAccUnits(pod, results); convertMagUnits(pod, results); convertGyroUnits(pod, results); - - (void) fclose(fd); + (void)fclose(fd); return results; } -std::string MPU9250Data::toJsonString() const { +std::string MPU9250Data::toJsonString() const +{ std::stringstream ss; ss << "{"; diff --git a/user/infrared/Makefile b/user/infrared/Makefile new file mode 100644 index 0000000..f0666a0 --- /dev/null +++ b/user/infrared/Makefile @@ -0,0 +1,28 @@ +APP_NAME=infrared + +CPPFLAGS=-Wall -Werror -pedantic -std=c++17 -O0 -g +# Attention: the lib diretory where the MQTT is installed into may not be in the LD path! +LDFLAGS=-lpaho-mqtt3a -lpaho-mqttpp3 -lfpgaregion -lpthread + +SOURCES=$(wildcard *.cpp) +OBJECTS=$(SOURCES:.cpp=.o) + + +all: $(APP_NAME) + +$(APP_NAME): $(OBJECTS) + $(CXX) $^ $(LDFLAGS) -o $@ + +%.o: %.cpp + $(CXX) -c $< $(CPPFLAGS) -o $@ + +clean: + rm -rf $(OBJECTS) + rm -rf $(APP_NAME) + +deploy: all + scp $(APP_NAME) $(DEPLOYSSH):$(DEPLOYSSHPATH)/$(APP_NAME) +# ssh $(DEPLOYSSH) $(DEPLOYSSHPATH)/$(APP_NAME) + + +.PHONY: all clean deploy diff --git a/user/infrared/fpga.cpp b/user/infrared/fpga.cpp new file mode 100644 index 0000000..f3a03c7 --- /dev/null +++ b/user/infrared/fpga.cpp @@ -0,0 +1,39 @@ +#include "fpga.h" + +#include + +#include +#include +#include + + +static std::mutex fpgaMutex; +static std::unique_ptr fpga; + + +static void ReconfigRequested() { + std::cout << "Reconfiguration in progres" << std::endl; + fpgaMutex.lock(); + fpga->Release(); + std::cout << "Reconfiguration requested" << std::endl; +} + +static void ReconfigDone() { + std::cout << "Reconfiguration done" << std::endl; + fpga->Acquire(); + fpgaMutex.unlock(); +} + + + + +void initFPGA(std::string name) { + fpga = std::make_unique(name, ReconfigRequested, ReconfigDone); + fpga->Acquire(); +} + + +std::lock_guard lockFPGA() { + assert(fpga); + return std::lock_guard(fpgaMutex); +} diff --git a/user/infrared/fpga.h b/user/infrared/fpga.h new file mode 100644 index 0000000..8f58db0 --- /dev/null +++ b/user/infrared/fpga.h @@ -0,0 +1,11 @@ +#ifndef FPGA_H +#define FPGA_H + +#include +#include + + +void initFPGA(std::string name); +std::lock_guard lockFPGA(); + +#endif diff --git a/user/infrared/main.cpp b/user/infrared/main.cpp new file mode 100644 index 0000000..b6a3ff9 --- /dev/null +++ b/user/infrared/main.cpp @@ -0,0 +1,139 @@ +#include "fpga.h" + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +using namespace std::literals::chrono_literals; + +static const std::string CHARACTER_DEVICE = "/dev/infrared"; + +#define IOC_SET_PID 0 +#define IOC_CMD_SET_PID _IO(4711, IOC_SET_PID) + +/* Event specific defines */ +#define EVENT_SIGNAL_NR 12 // (SIGUSR2) + +struct INFRARED +{ + uint32_t timestamp[256]; + uint32_t magic_number[4]; +} __attribute__((packed)); + +static void interrupt_handler(int, siginfo_t *, void *) +{ + std::cout << "INFRARED An interrupt occured! :)" << std::endl; + + // TODO + // 1. Read timestamps + // 2. Write them into FPGA send-buffer + // 3. Set "send bit" in control register + // -- sets LED high + // -- sequence is sent by press of a button (mirror button on another LED)) +} + +void setup_interrupt_signalling() +{ + auto fd = fopen(CHARACTER_DEVICE.c_str(), "rb"); + if (!fd) + { + std::cerr << "Failed to open character device '" << CHARACTER_DEVICE << "'" << std::endl; + return; + } + + if (ioctl(fileno(fd), IOC_CMD_SET_PID) < 0) + { + std::cerr << "Failed to set PID: " << strerror(errno) << std::endl; + fclose(fd); + return; + } + + fclose(fd); + + struct sigaction sig; + sig.sa_sigaction = interrupt_handler; + sig.sa_flags = SA_SIGINFO; + sigaction(EVENT_SIGNAL_NR, &sig, NULL); +} + +std::optional readFromCDev() +{ + + INFRARED results; + + // lock fpga device using a lock guard + // the result is never used, but it keeps the mutex locked until it goes out of scope + auto _lck = lockFPGA(); + + // open character device + auto fd = fopen(CHARACTER_DEVICE.c_str(), "rb"); + if (!fd) + { + std::cerr << "Failed to open character device '" << CHARACTER_DEVICE << "'" << std::endl; + return {}; + } + + if (fread(&results, sizeof(INFRARED), 1, fd) != 1) + { + std::cerr << "Failed to read sensor values" << std::endl; + (void)fclose(fd); + return {}; + } + + (void)fclose(fd); + + return std::make_optional(results); +} + +std::string formatDataToString(INFRARED payload) +{ + std::stringstream ss; + ss << "magic_number[0]: 0x" << std::hex << payload.magic_number[0] << std::endl; + ss << "magic_number[1]: 0x" << std::hex << payload.magic_number[1] << std::endl; + ss << "magic_number[2]: 0x" << std::hex << payload.magic_number[2] << std::endl; + ss << "magic_number[3]: 0x" << std::hex << payload.magic_number[3] << std::endl; + for (int i = 0; i < 10; i++) + ss << "timestamp[" << i << "]=" << std::hex << payload.timestamp[i] << std::endl; + + return ss.str(); +} + +int main() +{ + try + { + initFPGA("INFRARED"); + } + catch (const std::string &s) + { + std::cerr << "Failed to initialize FPGA: " << s << std::endl; + return -1; + } + + setup_interrupt_signalling(); + while (1) + { + std::this_thread::sleep_for(1000ms); + + auto optValues = readFromCDev(); + if (!optValues.has_value()) + { + std::cerr << "INFRARED Failed to read device." << std::endl; + continue; + } + + auto values = optValues.value(); + std::cout << formatDataToString(values) << std::endl; + } + + return 0; +} diff --git a/vhdltool-config.yaml b/vhdltool-config.yaml new file mode 100644 index 0000000..8f4db44 --- /dev/null +++ b/vhdltool-config.yaml @@ -0,0 +1,44 @@ +#Define your project's libraries and source files here. +#This section is compulsory. +Libraries: + #The name of the library. + - name: work + #The paths where the source files for this library can be found. Use "**" to match arbitrarily nested directories. + paths: + - "**/infrared/*.vhd" + +#Enable/disable typechecking +TypeCheck: True + +#Enable/disable check-as-you-type +CheckOnChange: True + +#Linter rule configuration. +#Rules can be enabled or disabled. +#Rules also have a severity. It may be one of Info, Warning, Critical or Error. +Lint: + #Threshold, below which messages are not displayed. + Threshold: Warning + + #Long form rule configuration. Both enabled/disabled status and severity can be configured this way. + DeclaredNotAssigned: + enabled: True + severity: Warning #Default severity Warning + + #Short form. Only enabled/disabled status can be specified. Severity is the default for the rule. + DeclaredNotRead: True #Default severity Warning + ReadNotAssigned: True #Default severity Critical + SensitivityListCheck: True #Default severity Warning + ExtraSensitivityListCheck: True #Default severity Warning + DuplicateSensitivity: True #Default severity Warning + LatchCheck: True #Default severity Critical + VariableNotRead: True #Default severity Warning + VariableNotWritten: True #Default severity Warning + PortNotRead: True #Default severity Warning + PortNotWritten: True #Default severity Critical + NoPrimaryUnit: True #Default severity Warning + DuplicateLibraryImport: True #Default severity Warning + DuplicatePackageUsage: True #Default severity Warning + DeprecatedPackages: True #Default severity Warning + ImplicitLibraries: True #Default severity Warning + DisconnectedPorts: True #Default severity Critical