mirror of
https://github.com/NawfalMotii79/PLFM_RADAR.git
synced 2026-04-19 11:36:01 +00:00
Compare commits
51 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| d0b3a4c969 | |||
| 582476fa0d | |||
| 7c91a3e0b9 | |||
| fd6cff5b2b | |||
| 964f1903f3 | |||
| 12b549dafb | |||
| 5d5e9ff297 | |||
| 754d919e44 | |||
| 0443516cc9 | |||
| 5fbe0513b5 | |||
| c3db8a9122 | |||
| ec8256e25a | |||
| 8e1b3f22d2 | |||
| 15ae940be5 | |||
| 658752abb7 | |||
| fa5e1dcdf4 | |||
| ade1497457 | |||
| f1d3bff4fe | |||
| 791b2e7374 | |||
| df875bdf4d | |||
| 15a9cde274 | |||
| ae7643975d | |||
| 8609e455a0 | |||
| 029df375f5 | |||
| a9ceb3c851 | |||
| 425c349184 | |||
| bcbbfabbdb | |||
| b9c36dcca5 | |||
| db4e73577e | |||
| 35539ea934 | |||
| 8187771ab0 | |||
| b0e5b298fe | |||
| f67440ee9a | |||
| 513e0b9a69 | |||
| 78dff2fd3d | |||
| 0b25db08b5 | |||
| 4900282042 | |||
| 3f4513fec2 | |||
| a2686b7424 | |||
| cf3d288268 | |||
| 1c7861bb0d | |||
| d8d30a6315 | |||
| 34ecaf360b | |||
| 24b8442e40 | |||
| 2387f7f29f | |||
| 609589349d | |||
| a16472480a | |||
| a12ea90cdf | |||
| 2cb56e8b13 | |||
| 6bde91298d | |||
| 77496ccc88 |
@@ -46,7 +46,7 @@ jobs:
|
|||||||
- name: Unit tests
|
- name: Unit tests
|
||||||
run: >
|
run: >
|
||||||
uv run pytest
|
uv run pytest
|
||||||
9_Firmware/9_3_GUI/test_radar_dashboard.py
|
9_Firmware/9_3_GUI/test_GUI_V65_Tk.py
|
||||||
9_Firmware/9_3_GUI/test_v7.py
|
9_Firmware/9_3_GUI/test_v7.py
|
||||||
-v --tb=short
|
-v --tb=short
|
||||||
|
|
||||||
|
|||||||
Binary file not shown.
@@ -550,7 +550,7 @@
|
|||||||
<text x="3.085225" y="81.68279375" size="1.778" layer="51">GND</text>
|
<text x="3.085225" y="81.68279375" size="1.778" layer="51">GND</text>
|
||||||
<text x="2.3" y="53.85" size="1.778" layer="51">GND</text>
|
<text x="2.3" y="53.85" size="1.778" layer="51">GND</text>
|
||||||
<text x="3.336225" y="42.247028125" size="1.778" layer="51">GND</text>
|
<text x="3.336225" y="42.247028125" size="1.778" layer="51">GND</text>
|
||||||
<text x="2.25" y="11.75" size="1.778" layer="51">GND</text>
|
<text x="2.99881875" y="12.58869375" size="1.778" layer="51">GND</text>
|
||||||
<text x="21.75" y="12.15" size="1.778" layer="51" rot="R90">GND</text>
|
<text x="21.75" y="12.15" size="1.778" layer="51" rot="R90">GND</text>
|
||||||
<text x="37.45" y="10.05" size="1.778" layer="51" rot="R90">GND</text>
|
<text x="37.45" y="10.05" size="1.778" layer="51" rot="R90">GND</text>
|
||||||
<text x="60.5" y="9.4" size="1.778" layer="51" rot="R90">GND</text>
|
<text x="60.5" y="9.4" size="1.778" layer="51" rot="R90">GND</text>
|
||||||
@@ -589,11 +589,11 @@
|
|||||||
<text x="248.95" y="49.2" size="1.778" layer="51" rot="R180">GND</text>
|
<text x="248.95" y="49.2" size="1.778" layer="51" rot="R180">GND</text>
|
||||||
<text x="248.85" y="66.55" size="1.778" layer="51" rot="R180">GND</text>
|
<text x="248.85" y="66.55" size="1.778" layer="51" rot="R180">GND</text>
|
||||||
<text x="248.8" y="82.9" size="1.778" layer="51" rot="R180">GND</text>
|
<text x="248.8" y="82.9" size="1.778" layer="51" rot="R180">GND</text>
|
||||||
<text x="256.35" y="101.95" size="1.778" layer="51" rot="R180">GND</text>
|
<text x="253.964015625" y="102.099125" size="1.778" layer="51" rot="R180">GND</text>
|
||||||
<text x="249.4" y="112.5" size="1.778" layer="51" rot="R180">GND</text>
|
<text x="249.054865625" y="112.111771875" size="1.778" layer="51" rot="R180">GND</text>
|
||||||
<text x="237.75" y="280.1" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="237.75" y="280.1" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="199.75" y="273.55" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="199.75" y="273.55" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="188.45" y="272.75" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="188.539503125" y="273.018421875" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="177.95" y="272.75" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="177.95" y="272.75" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="113.4" y="281.65" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="113.4" y="281.65" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="2.992190625" y="248.58331875" size="1.778" layer="51">GND</text>
|
<text x="2.992190625" y="248.58331875" size="1.778" layer="51">GND</text>
|
||||||
@@ -635,13 +635,13 @@
|
|||||||
<wire x1="161.6" y1="158.7" x2="156.95" y2="163.4" width="2.54" layer="29"/>
|
<wire x1="161.6" y1="158.7" x2="156.95" y2="163.4" width="2.54" layer="29"/>
|
||||||
<wire x1="170.1" y1="150.2" x2="165.45" y2="154.9" width="2.54" layer="29"/>
|
<wire x1="170.1" y1="150.2" x2="165.45" y2="154.9" width="2.54" layer="29"/>
|
||||||
<text x="125.137784375" y="269.740521875" size="1.778" layer="51" rot="R90">+5V0_PA_1</text>
|
<text x="125.137784375" y="269.740521875" size="1.778" layer="51" rot="R90">+5V0_PA_1</text>
|
||||||
<text x="185.45" y="267.2" size="1.778" layer="51" rot="R90">-3V4</text>
|
<text x="182.675396875" y="267.73684375" size="1.778" layer="51" rot="R90">-3V4</text>
|
||||||
<text x="196.5" y="267.4" size="1.778" layer="51" rot="R90">+3V4</text>
|
<text x="193.277878125" y="266.86315625" size="1.778" layer="51" rot="R90">+3V4</text>
|
||||||
<text x="207.4" y="267.85" size="1.778" layer="51" rot="R90">-5V0_ADAR12</text>
|
<text x="207.4" y="267.85" size="1.778" layer="51" rot="R90">-5V0_ADAR12</text>
|
||||||
<text x="188.75" y="289.05" size="1.3" layer="51" rot="R45">+3V3_ADAR12</text>
|
<text x="188.75" y="289.05" size="1.3" layer="51" rot="R45">+3V3_ADAR12</text>
|
||||||
<text x="248.25" y="270.6" size="1.778" layer="51" rot="R90">+5V0_PA_2</text>
|
<text x="248.25" y="270.6" size="1.778" layer="51" rot="R90">+5V0_PA_2</text>
|
||||||
<text x="242.8" y="98.7" size="1.778" layer="51" rot="R180">+3V4</text>
|
<text x="249.695853125" y="96.471690625" size="1.778" layer="51" rot="R180">+3V4</text>
|
||||||
<text x="242.9" y="106.65" size="1.778" layer="51" rot="R180">-3V4</text>
|
<text x="249.232640625" y="104.692303125" size="1.778" layer="51" rot="R180">-3V4</text>
|
||||||
<text x="181.4" y="99.15" size="1.778" layer="51" rot="R270">-5V0_ADAR34</text>
|
<text x="181.4" y="99.15" size="1.778" layer="51" rot="R270">-5V0_ADAR34</text>
|
||||||
<text x="185.3" y="75.15" size="1.778" layer="51" rot="R270">+3V3_ADAR34</text>
|
<text x="185.3" y="75.15" size="1.778" layer="51" rot="R270">+3V3_ADAR34</text>
|
||||||
<text x="238.95" y="72.8" size="1.778" layer="51">+3V3_VDD_SW</text>
|
<text x="238.95" y="72.8" size="1.778" layer="51">+3V3_VDD_SW</text>
|
||||||
@@ -714,8 +714,8 @@
|
|||||||
<text x="147.05" y="25.3" size="1.778" layer="51" rot="R180">CHAN14</text>
|
<text x="147.05" y="25.3" size="1.778" layer="51" rot="R180">CHAN14</text>
|
||||||
<text x="157.1" y="25.25" size="1.778" layer="51" rot="R180">CHAN15</text>
|
<text x="157.1" y="25.25" size="1.778" layer="51" rot="R180">CHAN15</text>
|
||||||
<text x="167.15" y="25.35" size="1.778" layer="51" rot="R180">CHAN16</text>
|
<text x="167.15" y="25.35" size="1.778" layer="51" rot="R180">CHAN16</text>
|
||||||
<text x="50.15" y="131.25" size="1.778" layer="51" rot="R180">SV1</text>
|
<text x="51.802165625" y="131.052934375" size="1.778" layer="51" rot="R180">SV1</text>
|
||||||
<text x="43.25" y="128.5" size="1.778" layer="51" rot="R270">VOLTAGE SEQUENCING</text>
|
<text x="35.60243125" y="132.092775" size="1.778" layer="51" rot="R270">VOLTAGE SEQUENCING</text>
|
||||||
<text x="105.55" y="106.9" size="1.2" layer="51" rot="R90">AD9523_EEPROM_SEL</text>
|
<text x="105.55" y="106.9" size="1.2" layer="51" rot="R90">AD9523_EEPROM_SEL</text>
|
||||||
<text x="107.2" y="101.85" size="1.2" layer="51" rot="R45">AD9523_STATUS0</text>
|
<text x="107.2" y="101.85" size="1.2" layer="51" rot="R45">AD9523_STATUS0</text>
|
||||||
<text x="107.25" y="99.35" size="1.2" layer="51" rot="R45">STM32_MOSI4</text>
|
<text x="107.25" y="99.35" size="1.2" layer="51" rot="R45">STM32_MOSI4</text>
|
||||||
@@ -728,20 +728,19 @@
|
|||||||
<text x="99.8" y="100.75" size="1.2" layer="51" rot="R225">STM32_MISO4</text>
|
<text x="99.8" y="100.75" size="1.2" layer="51" rot="R225">STM32_MISO4</text>
|
||||||
<text x="99.8" y="103.4" size="1.2" layer="51" rot="R225">AD9523_STATUS1</text>
|
<text x="99.8" y="103.4" size="1.2" layer="51" rot="R225">AD9523_STATUS1</text>
|
||||||
<text x="99.7" y="105.85" size="1.2" layer="51" rot="R225">GND</text>
|
<text x="99.7" y="105.85" size="1.2" layer="51" rot="R225">GND</text>
|
||||||
<text x="68.7" y="82.55" size="1.778" layer="51">JP4</text>
|
<text x="68.73355625" y="72.201796875" size="1.778" layer="51">JP4</text>
|
||||||
<text x="64.25" y="73.85" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="62.77508125" y="75.956934375" size="1" layer="51" rot="R225">GND</text>
|
||||||
<text x="56.95" y="82.75" size="1.778" layer="51">JP9</text>
|
<text x="56.95" y="82.75" size="1.778" layer="51">JP9</text>
|
||||||
<text x="37.85" y="78.6" size="1.778" layer="51" rot="R90">JP2</text>
|
<text x="45.798875" y="84.61879375" size="1.778" layer="51" rot="R180">JP2</text>
|
||||||
<text x="43.95" y="88.9" size="1.778" layer="51">JP8</text>
|
<text x="43.09716875" y="85.33433125" size="1.778" layer="51" rot="R90">JP8</text>
|
||||||
<text x="29.1" y="93.2" size="1.778" layer="51">JP7</text>
|
<text x="29.1" y="93.2" size="1.778" layer="51">IMU</text>
|
||||||
<text x="21.75" y="85.35" size="1.778" layer="51">JP18</text>
|
<text x="27.568784375" y="88.61074375" size="1.778" layer="51">JP18</text>
|
||||||
<text x="89.3" y="75.5" size="1.778" layer="51" rot="R180">JP13</text>
|
<text x="89.3" y="75.5" size="1.778" layer="51" rot="R180">JP13</text>
|
||||||
<text x="75.2" y="77" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="75.2" y="77" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="69.6" y="74.1" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="62.1909375" y="71.621040625" size="1.778" layer="51">JP10</text>
|
||||||
<text x="62.9" y="82.75" size="1.778" layer="51">JP10</text>
|
<text x="54.996875" y="70.359128125" size="1.2" layer="51">STEPPER</text>
|
||||||
<text x="53.75" y="64.4" size="1.2" layer="51" rot="R45">STEPPER_CLK+</text>
|
<text x="43.9" y="78.65" size="1.27" layer="51" rot="R270">GND</text>
|
||||||
<text x="43.9" y="78.65" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="52.61158125" y="88.897171875" size="1.016" layer="51" rot="R90">GND</text>
|
||||||
<text x="53.95" y="86.4" size="1.778" layer="51">GND</text>
|
|
||||||
<text x="31.3" y="84.75" size="1.778" layer="51" rot="R270">GND</text>
|
<text x="31.3" y="84.75" size="1.778" layer="51" rot="R270">GND</text>
|
||||||
<text x="40.45" y="95.9" size="1.778" layer="51" rot="R90">GND</text>
|
<text x="40.45" y="95.9" size="1.778" layer="51" rot="R90">GND</text>
|
||||||
<rectangle x1="12.8295" y1="256.5735" x2="15.6235" y2="256.7005" layer="51"/>
|
<rectangle x1="12.8295" y1="256.5735" x2="15.6235" y2="256.7005" layer="51"/>
|
||||||
@@ -5387,6 +5386,56 @@
|
|||||||
<text x="122.221528125" y="146.5440625" size="1.27" layer="51" rot="R315">RX 3_4</text>
|
<text x="122.221528125" y="146.5440625" size="1.27" layer="51" rot="R315">RX 3_4</text>
|
||||||
<text x="145.05015" y="114.518025" size="1.27" layer="51" rot="R45">RX 4_4</text>
|
<text x="145.05015" y="114.518025" size="1.27" layer="51" rot="R45">RX 4_4</text>
|
||||||
<text x="150.25345625" y="4.79933125" size="5.4864" layer="51" font="vector">www.abac-industry.com</text>
|
<text x="150.25345625" y="4.79933125" size="5.4864" layer="51" font="vector">www.abac-industry.com</text>
|
||||||
|
<text x="47.269546875" y="127.64274375" size="1.27" layer="51" rot="R135">+1V0_FPGA</text>
|
||||||
|
<text x="47.220515625" y="125.152134375" size="1.27" layer="51" rot="R135">+1V8_FPGA</text>
|
||||||
|
<text x="47.270815625" y="122.549565625" size="1.27" layer="51" rot="R135">+3V3_FPGA</text>
|
||||||
|
<text x="47.317503125" y="119.8292125" size="1.27" layer="51" rot="R135">+5V0_ADAR</text>
|
||||||
|
<text x="47.30423125" y="117.319196875" size="1.27" layer="51" rot="R135">+3V3_ADAR12</text>
|
||||||
|
<text x="47.2552" y="114.8285875" size="1.27" layer="51" rot="R135">+3V3_ADAR34</text>
|
||||||
|
<text x="47.3055" y="112.22601875" size="1.27" layer="51" rot="R135">+3V3_ADTR</text>
|
||||||
|
<text x="47.3521875" y="109.505665625" size="1.27" layer="51" rot="R135">+3V3_SW</text>
|
||||||
|
<text x="47.262328125" y="107.0494875" size="1.27" layer="51" rot="R135">+3V3_VDD_SW</text>
|
||||||
|
<text x="47.262328125" y="104.6232625" size="1.27" layer="51" rot="R135">+5V0_PA1</text>
|
||||||
|
<text x="52.848896875" y="114.716634375" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="52.897928125" y="117.20724375" size="1.27" layer="51" rot="R315">+3V3_CLOCK</text>
|
||||||
|
<text x="52.847628125" y="119.8098125" size="1.27" layer="51" rot="R315">+1V8_CLOCK</text>
|
||||||
|
<text x="52.800940625" y="122.530165625" size="1.27" layer="51" rot="R315">+5V5_PA</text>
|
||||||
|
<text x="52.8908" y="124.98634375" size="1.27" layer="51" rot="R315">+5V0_PA3</text>
|
||||||
|
<text x="52.8908" y="127.41256875" size="1.27" layer="51" rot="R315">+5V0_PA2</text>
|
||||||
|
<text x="52.866228125" y="112.238071875" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="52.79689375" y="109.7075125" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="52.7795625" y="107.038290625" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="52.762228125" y="104.50773125" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="37.741834375" y="95.9444" size="1.778" layer="51" rot="R90">+3V3</text>
|
||||||
|
<text x="43.11376875" y="95.9444" size="1.778" layer="51" rot="R90">SCL3</text>
|
||||||
|
<text x="45.64435" y="95.9888" size="1.778" layer="51" rot="R90">SDA3</text>
|
||||||
|
<text x="48.232090625" y="95.98181875" size="1.016" layer="51" rot="R90">MAG_DRDY</text>
|
||||||
|
<text x="50.801084375" y="95.879059375" size="1.016" layer="51" rot="R90">ACC_INT</text>
|
||||||
|
<text x="52.907659375" y="95.95613125" size="1.016" layer="51" rot="R90">GYR_INT</text>
|
||||||
|
<text x="54.502678125" y="92.739546875" size="1.778" layer="51">JP7</text>
|
||||||
|
<text x="30.45236875" y="78.6816375" size="1.778" layer="51" rot="R90">+3V3</text>
|
||||||
|
<text x="35.56853125" y="79.257065625" size="1.778" layer="51" rot="R90">SCL3</text>
|
||||||
|
<text x="38.227" y="78.789975" size="1.778" layer="51" rot="R90">SDA3</text>
|
||||||
|
<text x="39.282209375" y="78.488071875" size="1.27" layer="51" rot="R270">+3V3</text>
|
||||||
|
<text x="41.4419875" y="78.63334375" size="1.27" layer="51" rot="R270">STM32_SWCLK</text>
|
||||||
|
<text x="46.663971875" y="78.473509375" size="1.27" layer="51" rot="R270">STM32_SWDIO</text>
|
||||||
|
<text x="49.16839375" y="78.5267875" size="1.27" layer="51" rot="R270">STM32_NRST</text>
|
||||||
|
<text x="51.7793875" y="78.473509375" size="1.27" layer="51" rot="R270">STM32_SWO</text>
|
||||||
|
<text x="53.6100625" y="82.81805625" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="53.75804375" y="77.6019375" size="1.27" layer="51" rot="R315">GND</text>
|
||||||
|
<text x="53.809425" y="80.29940625" size="1.27" layer="51" rot="R315">CW+</text>
|
||||||
|
<text x="53.520859375" y="75.467190625" size="1.27" layer="51" rot="R315">CLK+</text>
|
||||||
|
<text x="50.081" y="88.941571875" size="1.016" layer="51" rot="R90">RX5</text>
|
||||||
|
<text x="47.417228125" y="88.985971875" size="1.016" layer="51" rot="R90">TX5</text>
|
||||||
|
<text x="45.019834375" y="88.675175" size="1.016" layer="51" rot="R90">+3V3</text>
|
||||||
|
<text x="53.525646875" y="86.07393125" size="1.778" layer="51">GPS</text>
|
||||||
|
<text x="62.34479375" y="80.785540625" size="0.9" layer="51" rot="R45">EN/DIS_RFPA_VDD</text>
|
||||||
|
<text x="68.0472625" y="76.328084375" size="1" layer="51" rot="R225">GND</text>
|
||||||
|
<text x="67.5982" y="80.711553125" size="0.9" layer="51" rot="R45">EN/DIS_COOLING</text>
|
||||||
|
<text x="78.325053125" y="83.140434375" size="1.778" layer="51">ADF4382</text>
|
||||||
|
<text x="92.67903125" y="80.894575" size="1.016" layer="51">1</text>
|
||||||
|
<text x="92.77235625" y="78.2390125" size="1.016" layer="51">2</text>
|
||||||
|
<text x="73.362715625" y="77.945809375" size="1.016" layer="51">14</text>
|
||||||
</plain>
|
</plain>
|
||||||
<libraries>
|
<libraries>
|
||||||
<library name="eagle-ltspice">
|
<library name="eagle-ltspice">
|
||||||
@@ -24576,8 +24625,8 @@ Your PCBWay Team
|
|||||||
<vertex x="114" y="112" curve="-180"/>
|
<vertex x="114" y="112" curve="-180"/>
|
||||||
</polygon>
|
</polygon>
|
||||||
<polygon width="0.254" layer="1" spacing="5.08">
|
<polygon width="0.254" layer="1" spacing="5.08">
|
||||||
<vertex x="258.75" y="116" curve="-180"/>
|
<vertex x="258.9164" y="116.0208" curve="-180"/>
|
||||||
<vertex x="254.75" y="112" curve="-180"/>
|
<vertex x="254.9164" y="112.0208" curve="-180"/>
|
||||||
</polygon>
|
</polygon>
|
||||||
<polygon width="0.254" layer="1" spacing="5.08">
|
<polygon width="0.254" layer="1" spacing="5.08">
|
||||||
<vertex x="260" y="300"/>
|
<vertex x="260" y="300"/>
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -18,7 +18,7 @@ ADAR1000_AGC::ADAR1000_AGC()
|
|||||||
, min_gain(0)
|
, min_gain(0)
|
||||||
, max_gain(127)
|
, max_gain(127)
|
||||||
, holdoff_frames(4)
|
, holdoff_frames(4)
|
||||||
, enabled(true)
|
, enabled(false)
|
||||||
, holdoff_counter(0)
|
, holdoff_counter(0)
|
||||||
, last_saturated(false)
|
, last_saturated(false)
|
||||||
, saturation_event_count(0)
|
, saturation_event_count(0)
|
||||||
|
|||||||
@@ -20,18 +20,71 @@ static const struct {
|
|||||||
{ADAR_4_CS_3V3_GPIO_Port, ADAR_4_CS_3V3_Pin} // ADAR1000 #4
|
{ADAR_4_CS_3V3_GPIO_Port, ADAR_4_CS_3V3_Pin} // ADAR1000 #4
|
||||||
};
|
};
|
||||||
|
|
||||||
// Vector Modulator lookup tables
|
// ADAR1000 Vector Modulator lookup tables (128-state phase grid, 2.8125 deg step).
|
||||||
|
//
|
||||||
|
// Source: Analog Devices ADAR1000 datasheet Rev. B, Tables 13-16, page 34
|
||||||
|
// (7_Components Datasheets and Application notes/ADAR1000.pdf)
|
||||||
|
// Cross-checked against the ADI Linux mainline driver (GPL-2.0, NOT vendored):
|
||||||
|
// https://git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/
|
||||||
|
// drivers/iio/beamformer/adar1000.c (adar1000_phase_values[])
|
||||||
|
// The 128 byte values themselves are factual data from the datasheet and are
|
||||||
|
// not subject to copyright; only the ADI driver code is GPL.
|
||||||
|
//
|
||||||
|
// Byte format (per datasheet):
|
||||||
|
// bit [7:6] reserved (0)
|
||||||
|
// bit [5] polarity: 1 = positive lobe (sign(I) or sign(Q) >= 0)
|
||||||
|
// 0 = negative lobe
|
||||||
|
// bits [4:0] 5-bit unsigned magnitude (0..31)
|
||||||
|
// At magnitude=0 the polarity bit is physically meaningless; the datasheet
|
||||||
|
// uses POL=1 (e.g. VM_Q at 0 deg = 0x20, VM_I at 90 deg = 0x21).
|
||||||
|
//
|
||||||
|
// Index mapping is uniform: VM_I[k] / VM_Q[k] correspond to phase angle
|
||||||
|
// k * 360/128 = k * 2.8125 degrees. Callers index as VM_*[phase % 128].
|
||||||
const uint8_t ADAR1000Manager::VM_I[128] = {
|
const uint8_t ADAR1000Manager::VM_I[128] = {
|
||||||
// ... (same as in your original file)
|
0x3F, 0x3F, 0x3F, 0x3F, 0x3F, 0x3E, 0x3E, 0x3D, // [ 0] 0.0000 deg
|
||||||
|
0x3D, 0x3C, 0x3C, 0x3B, 0x3A, 0x39, 0x38, 0x37, // [ 8] 22.5000 deg
|
||||||
|
0x36, 0x35, 0x34, 0x33, 0x32, 0x30, 0x2F, 0x2E, // [ 16] 45.0000 deg
|
||||||
|
0x2C, 0x2B, 0x2A, 0x28, 0x27, 0x25, 0x24, 0x22, // [ 24] 67.5000 deg
|
||||||
|
0x21, 0x01, 0x03, 0x04, 0x06, 0x07, 0x08, 0x0A, // [ 32] 90.0000 deg
|
||||||
|
0x0B, 0x0D, 0x0E, 0x0F, 0x11, 0x12, 0x13, 0x14, // [ 40] 112.5000 deg
|
||||||
|
0x16, 0x17, 0x18, 0x19, 0x19, 0x1A, 0x1B, 0x1C, // [ 48] 135.0000 deg
|
||||||
|
0x1C, 0x1D, 0x1E, 0x1E, 0x1E, 0x1F, 0x1F, 0x1F, // [ 56] 157.5000 deg
|
||||||
|
0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1E, 0x1E, 0x1D, // [ 64] 180.0000 deg
|
||||||
|
0x1D, 0x1C, 0x1C, 0x1B, 0x1A, 0x19, 0x18, 0x17, // [ 72] 202.5000 deg
|
||||||
|
0x16, 0x15, 0x14, 0x13, 0x12, 0x10, 0x0F, 0x0E, // [ 80] 225.0000 deg
|
||||||
|
0x0C, 0x0B, 0x0A, 0x08, 0x07, 0x05, 0x04, 0x02, // [ 88] 247.5000 deg
|
||||||
|
0x01, 0x21, 0x23, 0x24, 0x26, 0x27, 0x28, 0x2A, // [ 96] 270.0000 deg
|
||||||
|
0x2B, 0x2D, 0x2E, 0x2F, 0x31, 0x32, 0x33, 0x34, // [104] 292.5000 deg
|
||||||
|
0x36, 0x37, 0x38, 0x39, 0x39, 0x3A, 0x3B, 0x3C, // [112] 315.0000 deg
|
||||||
|
0x3C, 0x3D, 0x3E, 0x3E, 0x3E, 0x3F, 0x3F, 0x3F, // [120] 337.5000 deg
|
||||||
};
|
};
|
||||||
|
|
||||||
const uint8_t ADAR1000Manager::VM_Q[128] = {
|
const uint8_t ADAR1000Manager::VM_Q[128] = {
|
||||||
// ... (same as in your original file)
|
0x20, 0x21, 0x23, 0x24, 0x26, 0x27, 0x28, 0x2A, // [ 0] 0.0000 deg
|
||||||
|
0x2B, 0x2D, 0x2E, 0x2F, 0x30, 0x31, 0x33, 0x34, // [ 8] 22.5000 deg
|
||||||
|
0x35, 0x36, 0x37, 0x38, 0x38, 0x39, 0x3A, 0x3A, // [ 16] 45.0000 deg
|
||||||
|
0x3B, 0x3C, 0x3C, 0x3C, 0x3D, 0x3D, 0x3D, 0x3D, // [ 24] 67.5000 deg
|
||||||
|
0x3D, 0x3D, 0x3D, 0x3D, 0x3D, 0x3C, 0x3C, 0x3C, // [ 32] 90.0000 deg
|
||||||
|
0x3B, 0x3A, 0x3A, 0x39, 0x38, 0x38, 0x37, 0x36, // [ 40] 112.5000 deg
|
||||||
|
0x35, 0x34, 0x33, 0x31, 0x30, 0x2F, 0x2E, 0x2D, // [ 48] 135.0000 deg
|
||||||
|
0x2B, 0x2A, 0x28, 0x27, 0x26, 0x24, 0x23, 0x21, // [ 56] 157.5000 deg
|
||||||
|
0x20, 0x01, 0x03, 0x04, 0x06, 0x07, 0x08, 0x0A, // [ 64] 180.0000 deg
|
||||||
|
0x0B, 0x0D, 0x0E, 0x0F, 0x10, 0x11, 0x13, 0x14, // [ 72] 202.5000 deg
|
||||||
|
0x15, 0x16, 0x17, 0x18, 0x18, 0x19, 0x1A, 0x1A, // [ 80] 225.0000 deg
|
||||||
|
0x1B, 0x1C, 0x1C, 0x1C, 0x1D, 0x1D, 0x1D, 0x1D, // [ 88] 247.5000 deg
|
||||||
|
0x1D, 0x1D, 0x1D, 0x1D, 0x1D, 0x1C, 0x1C, 0x1C, // [ 96] 270.0000 deg
|
||||||
|
0x1B, 0x1A, 0x1A, 0x19, 0x18, 0x18, 0x17, 0x16, // [104] 292.5000 deg
|
||||||
|
0x15, 0x14, 0x13, 0x11, 0x10, 0x0F, 0x0E, 0x0D, // [112] 315.0000 deg
|
||||||
|
0x0B, 0x0A, 0x08, 0x07, 0x06, 0x04, 0x03, 0x01, // [120] 337.5000 deg
|
||||||
};
|
};
|
||||||
|
|
||||||
const uint8_t ADAR1000Manager::VM_GAIN[128] = {
|
// NOTE: a VM_GAIN[128] table previously existed here as a placeholder but was
|
||||||
// ... (same as in your original file)
|
// never populated and never read. The ADAR1000 vector modulator has no
|
||||||
};
|
// separate gain register: phase-state magnitude is encoded directly in
|
||||||
|
// bits [4:0] of the VM_I/VM_Q bytes above. Per-channel VGA gain is a
|
||||||
|
// distinct register (CHx_RX_GAIN at 0x10-0x13, CHx_TX_GAIN at 0x1C-0x1F)
|
||||||
|
// written with the user-supplied byte directly by adarSetRxVgaGain() /
|
||||||
|
// adarSetTxVgaGain(). Do not reintroduce a VM_GAIN[] array.
|
||||||
|
|
||||||
ADAR1000Manager::ADAR1000Manager() {
|
ADAR1000Manager::ADAR1000Manager() {
|
||||||
for (int i = 0; i < 4; ++i) {
|
for (int i = 0; i < 4; ++i) {
|
||||||
@@ -815,11 +868,22 @@ void ADAR1000Manager::adarSetRamBypass(uint8_t deviceIndex, uint8_t broadcast) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ADAR1000Manager::adarSetRxPhase(uint8_t deviceIndex, uint8_t channel, uint8_t phase, uint8_t broadcast) {
|
void ADAR1000Manager::adarSetRxPhase(uint8_t deviceIndex, uint8_t channel, uint8_t phase, uint8_t broadcast) {
|
||||||
|
// channel is 1-based (CH1..CH4) per API contract documented in
|
||||||
|
// ADAR1000_AGC.cpp and matching ADI datasheet terminology.
|
||||||
|
// Reject out-of-range early so a stale 0-based caller does not
|
||||||
|
// silently wrap to ((0-1) & 0x03) == 3 and write to CH4.
|
||||||
|
// See issue #90.
|
||||||
|
if (channel < 1 || channel > 4) {
|
||||||
|
DIAG("BF", "adarSetRxPhase: channel %u out of range [1..4], ignored", channel);
|
||||||
|
return;
|
||||||
|
}
|
||||||
uint8_t i_val = VM_I[phase % 128];
|
uint8_t i_val = VM_I[phase % 128];
|
||||||
uint8_t q_val = VM_Q[phase % 128];
|
uint8_t q_val = VM_Q[phase % 128];
|
||||||
|
|
||||||
uint32_t mem_addr_i = REG_CH1_RX_PHS_I + (channel & 0x03) * 2;
|
// Subtract 1 to convert 1-based channel to 0-based register offset
|
||||||
uint32_t mem_addr_q = REG_CH1_RX_PHS_Q + (channel & 0x03) * 2;
|
// before masking. See issue #90.
|
||||||
|
uint32_t mem_addr_i = REG_CH1_RX_PHS_I + ((channel - 1) & 0x03) * 2;
|
||||||
|
uint32_t mem_addr_q = REG_CH1_RX_PHS_Q + ((channel - 1) & 0x03) * 2;
|
||||||
|
|
||||||
adarWrite(deviceIndex, mem_addr_i, i_val, broadcast);
|
adarWrite(deviceIndex, mem_addr_i, i_val, broadcast);
|
||||||
adarWrite(deviceIndex, mem_addr_q, q_val, broadcast);
|
adarWrite(deviceIndex, mem_addr_q, q_val, broadcast);
|
||||||
@@ -827,11 +891,16 @@ void ADAR1000Manager::adarSetRxPhase(uint8_t deviceIndex, uint8_t channel, uint8
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ADAR1000Manager::adarSetTxPhase(uint8_t deviceIndex, uint8_t channel, uint8_t phase, uint8_t broadcast) {
|
void ADAR1000Manager::adarSetTxPhase(uint8_t deviceIndex, uint8_t channel, uint8_t phase, uint8_t broadcast) {
|
||||||
|
// channel is 1-based (CH1..CH4). See issue #90.
|
||||||
|
if (channel < 1 || channel > 4) {
|
||||||
|
DIAG("BF", "adarSetTxPhase: channel %u out of range [1..4], ignored", channel);
|
||||||
|
return;
|
||||||
|
}
|
||||||
uint8_t i_val = VM_I[phase % 128];
|
uint8_t i_val = VM_I[phase % 128];
|
||||||
uint8_t q_val = VM_Q[phase % 128];
|
uint8_t q_val = VM_Q[phase % 128];
|
||||||
|
|
||||||
uint32_t mem_addr_i = REG_CH1_TX_PHS_I + (channel & 0x03) * 2;
|
uint32_t mem_addr_i = REG_CH1_TX_PHS_I + ((channel - 1) & 0x03) * 2;
|
||||||
uint32_t mem_addr_q = REG_CH1_TX_PHS_Q + (channel & 0x03) * 2;
|
uint32_t mem_addr_q = REG_CH1_TX_PHS_Q + ((channel - 1) & 0x03) * 2;
|
||||||
|
|
||||||
adarWrite(deviceIndex, mem_addr_i, i_val, broadcast);
|
adarWrite(deviceIndex, mem_addr_i, i_val, broadcast);
|
||||||
adarWrite(deviceIndex, mem_addr_q, q_val, broadcast);
|
adarWrite(deviceIndex, mem_addr_q, q_val, broadcast);
|
||||||
@@ -839,13 +908,23 @@ void ADAR1000Manager::adarSetTxPhase(uint8_t deviceIndex, uint8_t channel, uint8
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ADAR1000Manager::adarSetRxVgaGain(uint8_t deviceIndex, uint8_t channel, uint8_t gain, uint8_t broadcast) {
|
void ADAR1000Manager::adarSetRxVgaGain(uint8_t deviceIndex, uint8_t channel, uint8_t gain, uint8_t broadcast) {
|
||||||
uint32_t mem_addr = REG_CH1_RX_GAIN + (channel & 0x03);
|
// channel is 1-based (CH1..CH4). See issue #90.
|
||||||
|
if (channel < 1 || channel > 4) {
|
||||||
|
DIAG("BF", "adarSetRxVgaGain: channel %u out of range [1..4], ignored", channel);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
uint32_t mem_addr = REG_CH1_RX_GAIN + ((channel - 1) & 0x03);
|
||||||
adarWrite(deviceIndex, mem_addr, gain, broadcast);
|
adarWrite(deviceIndex, mem_addr, gain, broadcast);
|
||||||
adarWrite(deviceIndex, REG_LOAD_WORKING, 0x1, broadcast);
|
adarWrite(deviceIndex, REG_LOAD_WORKING, 0x1, broadcast);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ADAR1000Manager::adarSetTxVgaGain(uint8_t deviceIndex, uint8_t channel, uint8_t gain, uint8_t broadcast) {
|
void ADAR1000Manager::adarSetTxVgaGain(uint8_t deviceIndex, uint8_t channel, uint8_t gain, uint8_t broadcast) {
|
||||||
uint32_t mem_addr = REG_CH1_TX_GAIN + (channel & 0x03);
|
// channel is 1-based (CH1..CH4). See issue #90.
|
||||||
|
if (channel < 1 || channel > 4) {
|
||||||
|
DIAG("BF", "adarSetTxVgaGain: channel %u out of range [1..4], ignored", channel);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
uint32_t mem_addr = REG_CH1_TX_GAIN + ((channel - 1) & 0x03);
|
||||||
adarWrite(deviceIndex, mem_addr, gain, broadcast);
|
adarWrite(deviceIndex, mem_addr, gain, broadcast);
|
||||||
adarWrite(deviceIndex, REG_LOAD_WORKING, LD_WRK_REGS_LDTX_OVERRIDE, broadcast);
|
adarWrite(deviceIndex, REG_LOAD_WORKING, LD_WRK_REGS_LDTX_OVERRIDE, broadcast);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -116,10 +116,12 @@ public:
|
|||||||
bool beam_sweeping_active_ = false;
|
bool beam_sweeping_active_ = false;
|
||||||
uint32_t last_beam_update_time_ = 0;
|
uint32_t last_beam_update_time_ = 0;
|
||||||
|
|
||||||
// Lookup tables
|
// Vector Modulator lookup tables (see ADAR1000_Manager.cpp for provenance).
|
||||||
static const uint8_t VM_I[128];
|
// Indexed as VM_*[phase % 128] on a uniform 2.8125 deg grid.
|
||||||
|
// No VM_GAIN[] table exists: VM magnitude is bits [4:0] of the I/Q bytes
|
||||||
|
// themselves; per-channel VGA gain uses a separate register.
|
||||||
|
static const uint8_t VM_I[128];
|
||||||
static const uint8_t VM_Q[128];
|
static const uint8_t VM_Q[128];
|
||||||
static const uint8_t VM_GAIN[128];
|
|
||||||
|
|
||||||
// Named defaults for the ADTR1107 and ADAR1000 power sequence.
|
// Named defaults for the ADTR1107 and ADAR1000 power sequence.
|
||||||
static constexpr uint8_t kDefaultTxVgaGain = 0x7F;
|
static constexpr uint8_t kDefaultTxVgaGain = 0x7F;
|
||||||
|
|||||||
@@ -1,693 +0,0 @@
|
|||||||
/**
|
|
||||||
* MIT License
|
|
||||||
*
|
|
||||||
* Copyright (c) 2020 Jimmy Pentz
|
|
||||||
*
|
|
||||||
* Reach me at: github.com/jgpentz, jpentz1(at)gmail.com
|
|
||||||
*
|
|
||||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
|
||||||
* of this software and associated documentation files (the "Software"), to deal
|
|
||||||
* in the Software without restriction, including without limitation the rights
|
|
||||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sells
|
|
||||||
* copies of the Software, and to permit persons to whom the Software is
|
|
||||||
* furnished to do so, subject to the following conditions:
|
|
||||||
*
|
|
||||||
* The above copyright notice and this permission notice shall be included in all
|
|
||||||
* copies or substantial portions of the Software.
|
|
||||||
*
|
|
||||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
|
||||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
|
||||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
|
||||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
|
||||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
|
||||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
|
||||||
* SOFTWARE.
|
|
||||||
*/
|
|
||||||
/* ADAR1000 4-Channel, X Band and Ku Band Beamformer */
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Includes
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
#include "main.h"
|
|
||||||
#include "stm32f7xx_hal.h"
|
|
||||||
#include "stm32f7xx_hal_spi.h"
|
|
||||||
#include "stm32f7xx_hal_gpio.h"
|
|
||||||
#include "adar1000.h"
|
|
||||||
|
|
||||||
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Preprocessor Definitions and Constants
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// VM_GAIN is 15 dB of gain in 128 steps. ~0.12 dB per step.
|
|
||||||
// A 15 dB attenuator can be applied on top of these values.
|
|
||||||
const uint8_t VM_GAIN[128] = {
|
|
||||||
0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0A, 0x0B, 0x0C, 0x0D, 0x0E, 0x0F,
|
|
||||||
0x10, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x1a, 0x1b, 0x1c, 0x1d, 0x1e, 0x1f,
|
|
||||||
0x20, 0x21, 0x22, 0x23, 0x24, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x2b, 0x2c, 0x2d, 0x2e, 0x2f,
|
|
||||||
0x30, 0x31, 0x32, 0x33, 0x34, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x3b, 0x3c, 0x3d, 0x3e, 0x3f,
|
|
||||||
0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a, 0x4b, 0x4c, 0x4d, 0x4e, 0x4f,
|
|
||||||
0x50, 0x51, 0x52, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x5b, 0x5c, 0x5d, 0x5e, 0x5f,
|
|
||||||
0x60, 0x61, 0x62, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6a, 0x6b, 0x6c, 0x6d, 0x6e, 0x6f,
|
|
||||||
0x70, 0x71, 0x72, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x7b, 0x7c, 0x7d, 0x7e, 0x7f,
|
|
||||||
};
|
|
||||||
|
|
||||||
// VM_I and VM_Q are the settings for the vector modulator. 128 steps in 360 degrees. ~2.813 degrees per step.
|
|
||||||
const uint8_t VM_I[128] = {
|
|
||||||
0x3F, 0x3F, 0x3F, 0x3F, 0x3F, 0x3E, 0x3E, 0x3D, 0x3D, 0x3C, 0x3C, 0x3B, 0x3A, 0x39, 0x38, 0x37,
|
|
||||||
0x36, 0x35, 0x34, 0x33, 0x32, 0x30, 0x2F, 0x2E, 0x2C, 0x2B, 0x2A, 0x28, 0x27, 0x25, 0x24, 0x22,
|
|
||||||
0x21, 0x01, 0x03, 0x04, 0x06, 0x07, 0x08, 0x0A, 0x0B, 0x0D, 0x0E, 0x0F, 0x11, 0x12, 0x13, 0x14,
|
|
||||||
0x16, 0x17, 0x18, 0x19, 0x19, 0x1A, 0x1B, 0x1C, 0x1C, 0x1D, 0x1E, 0x1E, 0x1E, 0x1F, 0x1F, 0x1F,
|
|
||||||
0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1E, 0x1E, 0x1D, 0x1D, 0x1C, 0x1C, 0x1B, 0x1A, 0x19, 0x18, 0x17,
|
|
||||||
0x16, 0x15, 0x14, 0x13, 0x12, 0x10, 0x0F, 0x0E, 0x0C, 0x0B, 0x0A, 0x08, 0x07, 0x05, 0x04, 0x02,
|
|
||||||
0x01, 0x21, 0x23, 0x24, 0x26, 0x27, 0x28, 0x2A, 0x2B, 0x2D, 0x2E, 0x2F, 0x31, 0x32, 0x33, 0x34,
|
|
||||||
0x36, 0x37, 0x38, 0x39, 0x39, 0x3A, 0x3B, 0x3C, 0x3C, 0x3D, 0x3E, 0x3E, 0x3E, 0x3F, 0x3F, 0x3F,
|
|
||||||
};
|
|
||||||
|
|
||||||
const uint8_t VM_Q[128] = {
|
|
||||||
0x20, 0x21, 0x23, 0x24, 0x26, 0x27, 0x28, 0x2A, 0x2B, 0x2D, 0x2E, 0x2F, 0x30, 0x31, 0x33, 0x34,
|
|
||||||
0x35, 0x36, 0x37, 0x38, 0x38, 0x39, 0x3A, 0x3A, 0x3B, 0x3C, 0x3C, 0x3C, 0x3D, 0x3D, 0x3D, 0x3D,
|
|
||||||
0x3D, 0x3D, 0x3D, 0x3D, 0x3D, 0x3C, 0x3C, 0x3C, 0x3B, 0x3A, 0x3A, 0x39, 0x38, 0x38, 0x37, 0x36,
|
|
||||||
0x35, 0x34, 0x33, 0x31, 0x30, 0x2F, 0x2E, 0x2D, 0x2B, 0x2A, 0x28, 0x27, 0x26, 0x24, 0x23, 0x21,
|
|
||||||
0x20, 0x01, 0x03, 0x04, 0x06, 0x07, 0x08, 0x0A, 0x0B, 0x0D, 0x0E, 0x0F, 0x10, 0x11, 0x13, 0x14,
|
|
||||||
0x15, 0x16, 0x17, 0x18, 0x18, 0x19, 0x1A, 0x1A, 0x1B, 0x1C, 0x1C, 0x1C, 0x1D, 0x1D, 0x1D, 0x1D,
|
|
||||||
0x1D, 0x1D, 0x1D, 0x1D, 0x1D, 0x1C, 0x1C, 0x1C, 0x1B, 0x1A, 0x1A, 0x19, 0x18, 0x18, 0x17, 0x16,
|
|
||||||
0x15, 0x14, 0x13, 0x11, 0x10, 0x0F, 0x0E, 0x0D, 0x0B, 0x0A, 0x08, 0x07, 0x06, 0x04, 0x03, 0x01,
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Function Definitions
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
/**
|
|
||||||
* @brief Initialize the ADC on the ADAR by setting the ADC with a 2 MHz clk,
|
|
||||||
* and then enable it.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @warning This is setup to only read temperature sensor data, not the power detectors.
|
|
||||||
*/
|
|
||||||
void Adar_AdcInit(const AdarDevice * p_adar, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t data;
|
|
||||||
|
|
||||||
data = ADAR1000_ADC_2MHZ_CLK | ADAR1000_ADC_EN;
|
|
||||||
|
|
||||||
Adar_Write(p_adar, REG_ADC_CONTROL, data, broadcast);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Read a byte of data from the ADAR.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns a byte of data that has been converted from the temperature sensor.
|
|
||||||
*
|
|
||||||
* @warning This is setup to only read temperature sensor data, not the power detectors.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_AdcRead(const AdarDevice * p_adar, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t data;
|
|
||||||
|
|
||||||
// Start the ADC conversion
|
|
||||||
Adar_Write(p_adar, REG_ADC_CONTROL, ADAR1000_ADC_ST_CONV, broadcast);
|
|
||||||
|
|
||||||
// This is blocking for now... wait until data is converted, then read it
|
|
||||||
while (!(Adar_Read(p_adar, REG_ADC_CONTROL) & 0x01))
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
data = Adar_Read(p_adar, REG_ADC_OUT);
|
|
||||||
|
|
||||||
return(data);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Requests the device info from a specific ADAR and stores it in the
|
|
||||||
* provided AdarDeviceInfo struct.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param info[out] Struct that contains the device info fields.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERROR_NOERROR if information was successfully received and stored in the struct.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_GetDeviceInfo(const AdarDevice * p_adar, AdarDeviceInfo * info)
|
|
||||||
{
|
|
||||||
*((uint8_t *)info) = Adar_Read(p_adar, 0x002);
|
|
||||||
info->chip_type = Adar_Read(p_adar, 0x003);
|
|
||||||
info->product_id = ((uint16_t)Adar_Read(p_adar, 0x004)) << 8;
|
|
||||||
info->product_id |= ((uint16_t)Adar_Read(p_adar, 0x005)) & 0x00ff;
|
|
||||||
info->scratchpad = Adar_Read(p_adar, 0x00A);
|
|
||||||
info->spi_rev = Adar_Read(p_adar, 0x00B);
|
|
||||||
info->vendor_id = ((uint16_t)Adar_Read(p_adar, 0x00C)) << 8;
|
|
||||||
info->vendor_id |= ((uint16_t)Adar_Read(p_adar, 0x00D)) & 0x00ff;
|
|
||||||
info->rev_id = Adar_Read(p_adar, 0x045);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Read the data that is stored in a single ADAR register.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param mem_addr Memory address of the register you wish to read from.
|
|
||||||
*
|
|
||||||
* @return Returns the byte of data that is stored in the desired register.
|
|
||||||
*
|
|
||||||
* @warning This function will clear ADDR_ASCN bits.
|
|
||||||
* @warning The ADAR does not allow for block reads.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_Read(const AdarDevice * p_adar, uint32_t mem_addr)
|
|
||||||
{
|
|
||||||
uint8_t instruction[3];
|
|
||||||
|
|
||||||
// Set SDO active
|
|
||||||
Adar_Write(p_adar, REG_INTERFACE_CONFIG_A, INTERFACE_CONFIG_A_SDO_ACTIVE, 0);
|
|
||||||
|
|
||||||
instruction[0] = 0x80 | ((p_adar->dev_addr & 0x03) << 5);
|
|
||||||
instruction[0] |= ((0xff00 & mem_addr) >> 8);
|
|
||||||
instruction[1] = (0xff & mem_addr);
|
|
||||||
instruction[2] = 0x00;
|
|
||||||
|
|
||||||
p_adar->Transfer(instruction, p_adar->p_rx_buffer, ADAR1000_RD_SIZE);
|
|
||||||
|
|
||||||
// Set SDO Inactive
|
|
||||||
Adar_Write(p_adar, REG_INTERFACE_CONFIG_A, 0, 0);
|
|
||||||
|
|
||||||
return(p_adar->p_rx_buffer[2]);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Block memory write to an ADAR device.
|
|
||||||
*
|
|
||||||
* @pre ADDR_ASCN bits in register zero must be set!
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param mem_addr Memory address of the register you wish to read from.
|
|
||||||
* @param p_data Pointer to block of data to transfer (must have two unused bytes preceding the data for instruction).
|
|
||||||
* @param size Size of data in bytes, including the two additional leading bytes.
|
|
||||||
*
|
|
||||||
* @warning First two bytes of data will be corrupted if you do not provide two unused leading bytes!
|
|
||||||
*/
|
|
||||||
void Adar_ReadBlock(const AdarDevice * p_adar, uint16_t mem_addr, uint8_t * p_data, uint32_t size)
|
|
||||||
{
|
|
||||||
// Set SDO active
|
|
||||||
Adar_Write(p_adar, REG_INTERFACE_CONFIG_A, INTERFACE_CONFIG_A_SDO_ACTIVE | INTERFACE_CONFIG_A_ADDR_ASCN, 0);
|
|
||||||
|
|
||||||
// Prepare command
|
|
||||||
p_data[0] = 0x80 | ((p_adar->dev_addr & 0x03) << 5);
|
|
||||||
p_data[0] |= ((mem_addr) >> 8) & 0x1F;
|
|
||||||
p_data[1] = (0xFF & mem_addr);
|
|
||||||
|
|
||||||
// Start the transfer
|
|
||||||
p_adar->Transfer(p_data, p_data, size);
|
|
||||||
|
|
||||||
Adar_Write(p_adar, REG_INTERFACE_CONFIG_A, 0, 0);
|
|
||||||
// Return nothing since we assume this is non-blocking and won't wait around
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Sets the Rx/Tx bias currents for the LNA, VM, and VGA to be in either
|
|
||||||
* low power setting or nominal setting.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param p_bias[in] An AdarBiasCurrents struct filled with bias settings
|
|
||||||
* as seen in the datasheet Table 6. SPI Settings for
|
|
||||||
* Different Power Modules
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERR_NOERROR if the bias currents were set
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetBiasCurrents(const AdarDevice * p_adar, AdarBiasCurrents * p_bias, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t bias = 0;
|
|
||||||
|
|
||||||
// RX LNA/VGA/VM bias
|
|
||||||
bias = (p_bias->rx_lna & 0x0f);
|
|
||||||
Adar_Write(p_adar, REG_BIAS_CURRENT_RX_LNA, bias, broadcast); // RX LNA bias
|
|
||||||
bias = (p_bias->rx_vga & 0x07 << 3) | (p_bias->rx_vm & 0x07);
|
|
||||||
Adar_Write(p_adar, REG_BIAS_CURRENT_RX, bias, broadcast); // RX VM/VGA bias
|
|
||||||
|
|
||||||
// TX VGA/VM/DRV bias
|
|
||||||
bias = (p_bias->tx_vga & 0x07 << 3) | (p_bias->tx_vm & 0x07);
|
|
||||||
Adar_Write(p_adar, REG_BIAS_CURRENT_TX, bias, broadcast); // TX VM/VGA bias
|
|
||||||
bias = (p_bias->tx_drv & 0x07);
|
|
||||||
Adar_Write(p_adar, REG_BIAS_CURRENT_TX_DRV, bias, broadcast); // TX DRV bias
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set the bias ON and bias OFF voltages for the four PA's and one LNA.
|
|
||||||
*
|
|
||||||
* @pre This will set all 5 bias ON values and all 5 bias OFF values at once.
|
|
||||||
* To enable these bias values, please see the data sheet and ensure that the BIAS_CTRL,
|
|
||||||
* LNA_BIAS_OUT_EN, TR_SOURCE, TX_EN, RX_EN, TR (input to chip), and PA_ON (input to chip)
|
|
||||||
* bits have all been properly set.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param bias_on_voltage Array that contains the bias ON voltages.
|
|
||||||
* @param bias_off_voltage Array that contains the bias OFF voltages.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERR_NOERROR if the bias currents were set
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetBiasVoltages(const AdarDevice * p_adar, uint8_t bias_on_voltage[5], uint8_t bias_off_voltage[5])
|
|
||||||
{
|
|
||||||
Adar_SetBit(p_adar, 0x30, 6, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x31, 2, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x38, 5, BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH1_BIAS_ON,bias_on_voltage[0], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH2_BIAS_ON,bias_on_voltage[1], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH3_BIAS_ON,bias_on_voltage[2], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH4_BIAS_ON,bias_on_voltage[3], BROADCAST_OFF);
|
|
||||||
|
|
||||||
Adar_Write(p_adar, REG_PA_CH1_BIAS_OFF,bias_off_voltage[0], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH2_BIAS_OFF,bias_off_voltage[1], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH3_BIAS_OFF,bias_off_voltage[2], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_PA_CH4_BIAS_OFF,bias_off_voltage[3], BROADCAST_OFF);
|
|
||||||
|
|
||||||
Adar_SetBit(p_adar, 0x30, 4, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x30, 6, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x31, 2, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x38, 5, BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_LNA_BIAS_ON,bias_on_voltage[4], BROADCAST_OFF);
|
|
||||||
Adar_Write(p_adar, REG_LNA_BIAS_OFF,bias_off_voltage[4], BROADCAST_OFF);
|
|
||||||
|
|
||||||
Adar_ResetBit(p_adar, 0x30, 7, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x31, 2, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x31, 4, BROADCAST_OFF);
|
|
||||||
Adar_SetBit(p_adar, 0x31, 7, BROADCAST_OFF);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Setup the ADAR to use settings that are transferred over SPI.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERR_NOERROR if the bias currents were set
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetRamBypass(const AdarDevice * p_adar, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t data;
|
|
||||||
|
|
||||||
data = (MEM_CTRL_BIAS_RAM_BYPASS | MEM_CTRL_BEAM_RAM_BYPASS);
|
|
||||||
|
|
||||||
Adar_Write(p_adar, REG_MEM_CTL, data, broadcast);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set the VGA gain value of a Receive channel in dB.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param channel Channel in which to set the gain (1-4).
|
|
||||||
* @param vga_gain_db Gain to be applied to the channel, ranging from 0 - 30 dB.
|
|
||||||
* (Intended operation >16 dB).
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERROR_NOERROR if the gain was successfully set.
|
|
||||||
* ADAR_ERROR_FAILED if an invalid channel was selected.
|
|
||||||
*
|
|
||||||
* @warning 0 dB or 15 dB step attenuator may also be turned on, which is why intended operation is >16 dB.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetRxVgaGain(const AdarDevice * p_adar, uint8_t channel, uint8_t vga_gain_db, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t vga_gain_bits = (uint8_t)(255*vga_gain_db/16);
|
|
||||||
uint32_t mem_addr = 0;
|
|
||||||
|
|
||||||
if((channel == 0) || (channel > 4))
|
|
||||||
{
|
|
||||||
return(ADAR_ERROR_FAILED);
|
|
||||||
}
|
|
||||||
|
|
||||||
mem_addr = REG_CH1_RX_GAIN + (channel & 0x03);
|
|
||||||
|
|
||||||
// Set gain
|
|
||||||
Adar_Write(p_adar, mem_addr, vga_gain_bits, broadcast);
|
|
||||||
|
|
||||||
// Load the new setting
|
|
||||||
Adar_Write(p_adar, REG_LOAD_WORKING, 0x1, broadcast);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set the phase of a given receive channel using the I/Q vector modulator.
|
|
||||||
*
|
|
||||||
* @pre According to the given @param phase, this sets the polarity (bit 5) and gain (bits 4-0)
|
|
||||||
* of the @param channel, and then loads them into the working register.
|
|
||||||
* A vector modulator I/Q look-up table has been provided at the beginning of this library.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param channel Channel in which to set the gain (1-4).
|
|
||||||
* @param phase Byte that is used to set the polarity (bit 5) and gain (bits 4-0).
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERROR_NOERROR if the phase was successfully set.
|
|
||||||
* ADAR_ERROR_FAILED if an invalid channel was selected.
|
|
||||||
*
|
|
||||||
* @note To obtain your phase:
|
|
||||||
* phase = degrees * 128;
|
|
||||||
* phase /= 360;
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetRxPhase(const AdarDevice * p_adar, uint8_t channel, uint8_t phase, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t i_val = 0;
|
|
||||||
uint8_t q_val = 0;
|
|
||||||
uint32_t mem_addr_i, mem_addr_q;
|
|
||||||
|
|
||||||
if((channel == 0) || (channel > 4))
|
|
||||||
{
|
|
||||||
return(ADAR_ERROR_FAILED);
|
|
||||||
}
|
|
||||||
|
|
||||||
//phase = phase % 128;
|
|
||||||
i_val = VM_I[phase];
|
|
||||||
q_val = VM_Q[phase];
|
|
||||||
|
|
||||||
mem_addr_i = REG_CH1_RX_PHS_I + (channel & 0x03) * 2;
|
|
||||||
mem_addr_q = REG_CH1_RX_PHS_Q + (channel & 0x03) * 2;
|
|
||||||
|
|
||||||
Adar_Write(p_adar, mem_addr_i, i_val, broadcast);
|
|
||||||
Adar_Write(p_adar, mem_addr_q, q_val, broadcast);
|
|
||||||
Adar_Write(p_adar, REG_LOAD_WORKING, 0x1, broadcast);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set the VGA gain value of a Tx channel in dB.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERROR_NOERROR if the bias was successfully set.
|
|
||||||
* ADAR_ERROR_FAILED if an invalid channel was selected.
|
|
||||||
*
|
|
||||||
* @warning 0 dB or 15 dB step attenuator may also be turned on, which is why intended operation is >16 dB.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetTxBias(const AdarDevice * p_adar, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t vga_bias_bits;
|
|
||||||
uint8_t drv_bias_bits;
|
|
||||||
uint32_t mem_vga_bias;
|
|
||||||
uint32_t mem_drv_bias;
|
|
||||||
|
|
||||||
mem_vga_bias = REG_BIAS_CURRENT_TX;
|
|
||||||
mem_drv_bias = REG_BIAS_CURRENT_TX_DRV;
|
|
||||||
|
|
||||||
// Set bias to nom
|
|
||||||
vga_bias_bits = 0x2D;
|
|
||||||
drv_bias_bits = 0x06;
|
|
||||||
|
|
||||||
// Set bias
|
|
||||||
Adar_Write(p_adar, mem_vga_bias, vga_bias_bits, broadcast);
|
|
||||||
// Set bias
|
|
||||||
Adar_Write(p_adar, mem_drv_bias, drv_bias_bits, broadcast);
|
|
||||||
|
|
||||||
// Load the new setting
|
|
||||||
Adar_Write(p_adar, REG_LOAD_WORKING, 0x2, broadcast);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set the VGA gain value of a Tx channel.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param channel Tx channel in which to set the gain, ranging from 1 - 4.
|
|
||||||
* @param gain Gain to be applied to the channel, ranging from 0 - 127,
|
|
||||||
* plus the MSb 15dB attenuator (Intended operation >16 dB).
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERROR_NOERROR if the gain was successfully set.
|
|
||||||
* ADAR_ERROR_FAILED if an invalid channel was selected.
|
|
||||||
*
|
|
||||||
* @warning 0 dB or 15 dB step attenuator may also be turned on, which is why intended operation is >16 dB.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetTxVgaGain(const AdarDevice * p_adar, uint8_t channel, uint8_t gain, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint32_t mem_addr;
|
|
||||||
|
|
||||||
if((channel == 0) || (channel > 4))
|
|
||||||
{
|
|
||||||
return(ADAR_ERROR_FAILED);
|
|
||||||
}
|
|
||||||
|
|
||||||
mem_addr = REG_CH1_TX_GAIN + (channel & 0x03);
|
|
||||||
|
|
||||||
// Set gain
|
|
||||||
Adar_Write(p_adar, mem_addr, gain, broadcast);
|
|
||||||
|
|
||||||
// Load the new setting
|
|
||||||
Adar_Write(p_adar, REG_LOAD_WORKING, LD_WRK_REGS_LDTX_OVERRIDE, broadcast);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set the phase of a given transmit channel using the I/Q vector modulator.
|
|
||||||
*
|
|
||||||
* @pre According to the given @param phase, this sets the polarity (bit 5) and gain (bits 4-0)
|
|
||||||
* of the @param channel, and then loads them into the working register.
|
|
||||||
* A vector modulator I/Q look-up table has been provided at the beginning of this library.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param channel Channel in which to set the gain (1-4).
|
|
||||||
* @param phase Byte that is used to set the polarity (bit 5) and gain (bits 4-0).
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @return Returns ADAR_ERROR_NOERROR if the phase was successfully set.
|
|
||||||
* ADAR_ERROR_FAILED if an invalid channel was selected.
|
|
||||||
*
|
|
||||||
* @note To obtain your phase:
|
|
||||||
* phase = degrees * 128;
|
|
||||||
* phase /= 360;
|
|
||||||
*/
|
|
||||||
uint8_t Adar_SetTxPhase(const AdarDevice * p_adar, uint8_t channel, uint8_t phase, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t i_val = 0;
|
|
||||||
uint8_t q_val = 0;
|
|
||||||
uint32_t mem_addr_i, mem_addr_q;
|
|
||||||
|
|
||||||
if((channel == 0) || (channel > 4))
|
|
||||||
{
|
|
||||||
return(ADAR_ERROR_FAILED);
|
|
||||||
}
|
|
||||||
|
|
||||||
//phase = phase % 128;
|
|
||||||
i_val = VM_I[phase];
|
|
||||||
q_val = VM_Q[phase];
|
|
||||||
|
|
||||||
mem_addr_i = REG_CH1_TX_PHS_I + (channel & 0x03) * 2;
|
|
||||||
mem_addr_q = REG_CH1_TX_PHS_Q + (channel & 0x03) * 2;
|
|
||||||
|
|
||||||
Adar_Write(p_adar, mem_addr_i, i_val, broadcast);
|
|
||||||
Adar_Write(p_adar, mem_addr_q, q_val, broadcast);
|
|
||||||
Adar_Write(p_adar, REG_LOAD_WORKING, 0x1, broadcast);
|
|
||||||
|
|
||||||
return(ADAR_ERROR_NOERROR);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Reset the whole ADAR device.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] ADAR pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
*/
|
|
||||||
void Adar_SoftReset(const AdarDevice * p_adar)
|
|
||||||
{
|
|
||||||
uint8_t instruction[3];
|
|
||||||
|
|
||||||
instruction[0] = ((p_adar->dev_addr & 0x03) << 5);
|
|
||||||
instruction[1] = 0x00;
|
|
||||||
instruction[2] = 0x81;
|
|
||||||
|
|
||||||
p_adar->Transfer(instruction, NULL, sizeof(instruction));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Reset ALL ADAR devices in the SPI chain.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
*/
|
|
||||||
void Adar_SoftResetAll(const AdarDevice * p_adar)
|
|
||||||
{
|
|
||||||
uint8_t instruction[3];
|
|
||||||
|
|
||||||
instruction[0] = 0x08;
|
|
||||||
instruction[1] = 0x00;
|
|
||||||
instruction[2] = 0x81;
|
|
||||||
|
|
||||||
p_adar->Transfer(instruction, NULL, sizeof(instruction));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Write a byte of @param data to the register located at @param mem_addr.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param mem_addr Memory address of the register you wish to read from.
|
|
||||||
* @param data Byte of data to be stored in the register.
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
if this set to BROADCAST_ON.
|
|
||||||
*
|
|
||||||
* @warning If writing the same data to multiple registers, use ADAR_WriteBlock.
|
|
||||||
*/
|
|
||||||
void Adar_Write(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t data, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t instruction[3];
|
|
||||||
|
|
||||||
if (broadcast)
|
|
||||||
{
|
|
||||||
instruction[0] = 0x08;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
instruction[0] = ((p_adar->dev_addr & 0x03) << 5);
|
|
||||||
}
|
|
||||||
|
|
||||||
instruction[0] |= (0x1F00 & mem_addr) >> 8;
|
|
||||||
instruction[1] = (0xFF & mem_addr);
|
|
||||||
instruction[2] = data;
|
|
||||||
|
|
||||||
p_adar->Transfer(instruction, NULL, sizeof(instruction));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Block memory write to an ADAR device.
|
|
||||||
*
|
|
||||||
* @pre ADDR_ASCN BITS IN REGISTER ZERO MUST BE SET!
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param mem_addr Memory address of the register you wish to read from.
|
|
||||||
* @param p_data[in] Pointer to block of data to transfer (must have two unused bytes
|
|
||||||
preceding the data for instruction).
|
|
||||||
* @param size Size of data in bytes, including the two additional leading bytes.
|
|
||||||
*
|
|
||||||
* @warning First two bytes of data will be corrupted if you do not provide two unused leading bytes!
|
|
||||||
*/
|
|
||||||
void Adar_WriteBlock(const AdarDevice * p_adar, uint16_t mem_addr, uint8_t * p_data, uint32_t size)
|
|
||||||
{
|
|
||||||
// Prepare command
|
|
||||||
p_data[0] = ((p_adar->dev_addr & 0x03) << 5);
|
|
||||||
p_data[0] |= ((mem_addr) >> 8) & 0x1F;
|
|
||||||
p_data[1] = (0xFF & mem_addr);
|
|
||||||
|
|
||||||
// Start the transfer
|
|
||||||
p_adar->Transfer(p_data, NULL, size);
|
|
||||||
|
|
||||||
// Return nothing since we assume this is non-blocking and won't wait around
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Set contents of the INTERFACE_CONFIG_A register.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param flags #INTERFACE_CONFIG_A_SOFTRESET, #INTERFACE_CONFIG_A_LSB_FIRST,
|
|
||||||
* #INTERFACE_CONFIG_A_ADDR_ASCN, #INTERFACE_CONFIG_A_SDO_ACTIVE
|
|
||||||
* @param broadcast Send the message as a broadcast to all ADARs in the SPI chain
|
|
||||||
* if this set to BROADCAST_ON.
|
|
||||||
*/
|
|
||||||
void Adar_WriteConfigA(const AdarDevice * p_adar, uint8_t flags, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
Adar_Write(p_adar, 0x00, flags, broadcast);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Write a byte of @param data to the register located at @param mem_addr and
|
|
||||||
* then read from the device and verify that the register was correctly set.
|
|
||||||
*
|
|
||||||
* @param p_adar[in] Adar pointer Which specifies the device and what function
|
|
||||||
* to use for SPI transfer.
|
|
||||||
* @param mem_addr Memory address of the register you wish to read from.
|
|
||||||
* @param data Byte of data to be stored in the register.
|
|
||||||
*
|
|
||||||
* @return Returns the number of attempts that it took to successfully write to a register,
|
|
||||||
* starting from zero.
|
|
||||||
* @warning This function currently only supports writes to a single regiter in a single ADAR.
|
|
||||||
*/
|
|
||||||
uint8_t Adar_WriteVerify(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t data)
|
|
||||||
{
|
|
||||||
uint8_t rx_data;
|
|
||||||
|
|
||||||
for (uint8_t ii = 0; ii < 3; ii++)
|
|
||||||
{
|
|
||||||
Adar_Write(p_adar, mem_addr, data, 0);
|
|
||||||
|
|
||||||
// Can't read back from an ADAR with HW address 0
|
|
||||||
if (!((p_adar->dev_addr) % 4))
|
|
||||||
{
|
|
||||||
return(ADAR_ERROR_INVALIDADDR);
|
|
||||||
}
|
|
||||||
rx_data = Adar_Read(p_adar, mem_addr);
|
|
||||||
if (rx_data == data)
|
|
||||||
{
|
|
||||||
return(ii);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return(ADAR_ERROR_FAILED);
|
|
||||||
}
|
|
||||||
|
|
||||||
void Adar_SetBit(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t bit, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t temp = Adar_Read(p_adar, mem_addr);
|
|
||||||
uint8_t data = temp|(1<<bit);
|
|
||||||
Adar_Write(p_adar,mem_addr, data,broadcast);
|
|
||||||
}
|
|
||||||
|
|
||||||
void Adar_ResetBit(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t bit, uint8_t broadcast)
|
|
||||||
{
|
|
||||||
uint8_t temp = Adar_Read(p_adar, mem_addr);
|
|
||||||
uint8_t data = temp&~(1<<bit);
|
|
||||||
Adar_Write(p_adar,mem_addr, data,broadcast);
|
|
||||||
}
|
|
||||||
|
|
||||||
@@ -1,294 +0,0 @@
|
|||||||
/**
|
|
||||||
* MIT License
|
|
||||||
*
|
|
||||||
* Copyright (c) 2020 Jimmy Pentz
|
|
||||||
*
|
|
||||||
* Reach me at: github.com/jgpentz, jpentz1( at )gmail.com
|
|
||||||
*
|
|
||||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
|
||||||
* of this software and associated documentation files (the "Software"), to deal
|
|
||||||
* in the Software without restriction, including without limitation the rights
|
|
||||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sells
|
|
||||||
* copies of the Software, and to permit persons to whom the Software is
|
|
||||||
* furnished to do so, subject to the following conditions:
|
|
||||||
*
|
|
||||||
* The above copyright notice and this permission notice shall be included in all
|
|
||||||
* copies or substantial portions of the Software.
|
|
||||||
*
|
|
||||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
|
||||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
|
||||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
|
||||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
|
||||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
|
||||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
|
||||||
* SOFTWARE.
|
|
||||||
*/
|
|
||||||
/* ADAR1000 4-Channel, X Band and Ku Band Beamformer */
|
|
||||||
#ifndef LIB_ADAR1000_H_
|
|
||||||
#define LIB_ADAR1000_H_
|
|
||||||
|
|
||||||
#ifndef NULL
|
|
||||||
#define NULL (0)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Includes
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
#include "main.h"
|
|
||||||
#include "stm32f7xx_hal.h"
|
|
||||||
#include "stm32f7xx_hal_spi.h"
|
|
||||||
#include "stm32f7xx_hal_gpio.h"
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <string.h>
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
extern "C" { // Prevent C++ name mangling
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Datatypes
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
extern SPI_HandleTypeDef hspi1;
|
|
||||||
extern const uint8_t VM_GAIN[128];
|
|
||||||
extern const uint8_t VM_I[128];
|
|
||||||
extern const uint8_t VM_Q[128];
|
|
||||||
|
|
||||||
/// A function pointer prototype for a SPI transfer, the 3 parameters would be
|
|
||||||
/// p_txData, p_rxData, and size (number of bytes to transfer), respectively.
|
|
||||||
typedef uint32_t (*Adar_SpiTransfer)( uint8_t *, uint8_t *, uint32_t);
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
uint8_t dev_addr; ///< 2-bit device hardware address, 0x00, 0x01, 0x10, 0x11
|
|
||||||
Adar_SpiTransfer Transfer; ///< Function pointer to the function used for SPI transfers
|
|
||||||
uint8_t * p_rx_buffer; ///< Data buffer to store received bytes into
|
|
||||||
}const AdarDevice;
|
|
||||||
|
|
||||||
|
|
||||||
/// Use this to store bias current values into, as seen in the datasheet
|
|
||||||
/// Table 6. SPI Settings for Different Power Modules
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
uint8_t rx_lna; ///< nominal: 8, low power: 5
|
|
||||||
uint8_t rx_vm; ///< nominal: 5, low power: 2
|
|
||||||
uint8_t rx_vga; ///< nominal: 10, low power: 3
|
|
||||||
uint8_t tx_vm; ///< nominal: 5, low power: 2
|
|
||||||
uint8_t tx_vga; ///< nominal: 5, low power: 5
|
|
||||||
uint8_t tx_drv; ///< nominal: 6, low power: 3
|
|
||||||
} AdarBiasCurrents;
|
|
||||||
|
|
||||||
/// Useful for queries regarding the device info
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
uint8_t norm_operating_mode : 2;
|
|
||||||
uint8_t cust_operating_mode : 2;
|
|
||||||
uint8_t dev_status : 4;
|
|
||||||
uint8_t chip_type;
|
|
||||||
uint16_t product_id;
|
|
||||||
uint8_t scratchpad;
|
|
||||||
uint8_t spi_rev;
|
|
||||||
uint16_t vendor_id;
|
|
||||||
uint8_t rev_id;
|
|
||||||
} AdarDeviceInfo;
|
|
||||||
|
|
||||||
/// Return types for functions in this library
|
|
||||||
typedef enum {
|
|
||||||
ADAR_ERROR_NOERROR = 0,
|
|
||||||
ADAR_ERROR_FAILED = 1,
|
|
||||||
ADAR_ERROR_INVALIDADDR = 2,
|
|
||||||
} AdarErrorCodes;
|
|
||||||
|
|
||||||
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Function Prototypes
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
void Adar_AdcInit(const AdarDevice * p_adar, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_AdcRead(const AdarDevice * p_adar, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_GetDeviceInfo(const AdarDevice * p_adar, AdarDeviceInfo * info);
|
|
||||||
|
|
||||||
uint8_t Adar_Read(const AdarDevice * p_adar, uint32_t mem_addr);
|
|
||||||
|
|
||||||
void Adar_ReadBlock(const AdarDevice * p_adar, uint16_t mem_addr, uint8_t * p_data, uint32_t size);
|
|
||||||
|
|
||||||
uint8_t Adar_SetBiasCurrents(const AdarDevice * p_adar, AdarBiasCurrents * p_bias, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_SetBiasVoltages(const AdarDevice * p_adar, uint8_t bias_on_voltage[5], uint8_t bias_off_voltage[5]);
|
|
||||||
|
|
||||||
uint8_t Adar_SetRamBypass(const AdarDevice * p_adar, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_SetRxVgaGain(const AdarDevice * p_adar, uint8_t channel, uint8_t vga_gain_db, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_SetRxPhase(const AdarDevice * p_adar, uint8_t channel, uint8_t phase, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_SetTxBias(const AdarDevice * p_adar, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_SetTxVgaGain(const AdarDevice * p_adar, uint8_t channel, uint8_t vga_gain_db, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
uint8_t Adar_SetTxPhase(const AdarDevice * p_adar, uint8_t channel, uint8_t phase, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
void Adar_SoftReset(const AdarDevice * p_adar);
|
|
||||||
|
|
||||||
void Adar_SoftResetAll(const AdarDevice * p_adar);
|
|
||||||
|
|
||||||
void Adar_Write(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t data, uint8_t broadcast_bit);
|
|
||||||
|
|
||||||
void Adar_WriteBlock(const AdarDevice * p_adar, uint16_t mem_addr, uint8_t * p_data, uint32_t size);
|
|
||||||
|
|
||||||
void Adar_WriteConfigA(const AdarDevice * p_adar, uint8_t flags, uint8_t broadcast);
|
|
||||||
|
|
||||||
uint8_t Adar_WriteVerify(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t data);
|
|
||||||
|
|
||||||
void Adar_SetBit(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t bit, uint8_t broadcast);
|
|
||||||
|
|
||||||
void Adar_ResetBit(const AdarDevice * p_adar, uint32_t mem_addr, uint8_t bit, uint8_t broadcast);
|
|
||||||
|
|
||||||
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Preprocessor Definitions and Constants
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
// Using BROADCAST_ON will send a command to all ADARs that share a bus
|
|
||||||
#define BROADCAST_OFF 0
|
|
||||||
#define BROADCAST_ON 1
|
|
||||||
|
|
||||||
// The minimum size of a read from the ADARs consists of 3 bytes
|
|
||||||
#define ADAR1000_RD_SIZE 3
|
|
||||||
|
|
||||||
// Address at which the TX RAM starts
|
|
||||||
#define ADAR_TX_RAM_START_ADDR 0x1800
|
|
||||||
|
|
||||||
// ADC Defines
|
|
||||||
#define ADAR1000_ADC_2MHZ_CLK 0x00
|
|
||||||
#define ADAR1000_ADC_EN 0x60
|
|
||||||
#define ADAR1000_ADC_ST_CONV 0x70
|
|
||||||
|
|
||||||
/* REGISTER DEFINITIONS */
|
|
||||||
#define REG_INTERFACE_CONFIG_A 0x000
|
|
||||||
#define REG_INTERFACE_CONFIG_B 0x001
|
|
||||||
#define REG_DEV_CONFIG 0x002
|
|
||||||
#define REG_SCRATCHPAD 0x00A
|
|
||||||
#define REG_TRANSFER 0x00F
|
|
||||||
#define REG_CH1_RX_GAIN 0x010
|
|
||||||
#define REG_CH2_RX_GAIN 0x011
|
|
||||||
#define REG_CH3_RX_GAIN 0x012
|
|
||||||
#define REG_CH4_RX_GAIN 0x013
|
|
||||||
#define REG_CH1_RX_PHS_I 0x014
|
|
||||||
#define REG_CH1_RX_PHS_Q 0x015
|
|
||||||
#define REG_CH2_RX_PHS_I 0x016
|
|
||||||
#define REG_CH2_RX_PHS_Q 0x017
|
|
||||||
#define REG_CH3_RX_PHS_I 0x018
|
|
||||||
#define REG_CH3_RX_PHS_Q 0x019
|
|
||||||
#define REG_CH4_RX_PHS_I 0x01A
|
|
||||||
#define REG_CH4_RX_PHS_Q 0x01B
|
|
||||||
#define REG_CH1_TX_GAIN 0x01C
|
|
||||||
#define REG_CH2_TX_GAIN 0x01D
|
|
||||||
#define REG_CH3_TX_GAIN 0x01E
|
|
||||||
#define REG_CH4_TX_GAIN 0x01F
|
|
||||||
#define REG_CH1_TX_PHS_I 0x020
|
|
||||||
#define REG_CH1_TX_PHS_Q 0x021
|
|
||||||
#define REG_CH2_TX_PHS_I 0x022
|
|
||||||
#define REG_CH2_TX_PHS_Q 0x023
|
|
||||||
#define REG_CH3_TX_PHS_I 0x024
|
|
||||||
#define REG_CH3_TX_PHS_Q 0x025
|
|
||||||
#define REG_CH4_TX_PHS_I 0x026
|
|
||||||
#define REG_CH4_TX_PHS_Q 0x027
|
|
||||||
#define REG_LOAD_WORKING 0x028
|
|
||||||
#define REG_PA_CH1_BIAS_ON 0x029
|
|
||||||
#define REG_PA_CH2_BIAS_ON 0x02A
|
|
||||||
#define REG_PA_CH3_BIAS_ON 0x02B
|
|
||||||
#define REG_PA_CH4_BIAS_ON 0x02C
|
|
||||||
#define REG_LNA_BIAS_ON 0x02D
|
|
||||||
#define REG_RX_ENABLES 0x02E
|
|
||||||
#define REG_TX_ENABLES 0x02F
|
|
||||||
#define REG_MISC_ENABLES 0x030
|
|
||||||
#define REG_SW_CONTROL 0x031
|
|
||||||
#define REG_ADC_CONTROL 0x032
|
|
||||||
#define REG_ADC_CONTROL_TEMP_EN 0xf0
|
|
||||||
#define REG_ADC_OUT 0x033
|
|
||||||
#define REG_BIAS_CURRENT_RX_LNA 0x034
|
|
||||||
#define REG_BIAS_CURRENT_RX 0x035
|
|
||||||
#define REG_BIAS_CURRENT_TX 0x036
|
|
||||||
#define REG_BIAS_CURRENT_TX_DRV 0x037
|
|
||||||
#define REG_MEM_CTL 0x038
|
|
||||||
#define REG_RX_CHX_MEM 0x039
|
|
||||||
#define REG_TX_CHX_MEM 0x03A
|
|
||||||
#define REG_RX_CH1_MEM 0x03D
|
|
||||||
#define REG_RX_CH2_MEM 0x03E
|
|
||||||
#define REG_RX_CH3_MEM 0x03F
|
|
||||||
#define REG_RX_CH4_MEM 0x040
|
|
||||||
#define REG_TX_CH1_MEM 0x041
|
|
||||||
#define REG_TX_CH2_MEM 0x042
|
|
||||||
#define REG_TX_CH3_MEM 0x043
|
|
||||||
#define REG_TX_CH4_MEM 0x044
|
|
||||||
#define REG_PA_CH1_BIAS_OFF 0x046
|
|
||||||
#define REG_PA_CH2_BIAS_OFF 0x047
|
|
||||||
#define REG_PA_CH3_BIAS_OFF 0x048
|
|
||||||
#define REG_PA_CH4_BIAS_OFF 0x049
|
|
||||||
#define REG_LNA_BIAS_OFF 0x04A
|
|
||||||
#define REG_TX_BEAM_STEP_START 0x04D
|
|
||||||
#define REG_TX_BEAM_STEP_STOP 0x04E
|
|
||||||
#define REG_RX_BEAM_STEP_START 0x04F
|
|
||||||
#define REG_RX_BEAM_STEP_STOP 0x050
|
|
||||||
|
|
||||||
// REGISTER CONSTANTS
|
|
||||||
#define INTERFACE_CONFIG_A_SOFTRESET ((1 << 7) | (1 << 0))
|
|
||||||
#define INTERFACE_CONFIG_A_LSB_FIRST ((1 << 6) | (1 << 1))
|
|
||||||
#define INTERFACE_CONFIG_A_ADDR_ASCN ((1 << 5) | (1 << 2))
|
|
||||||
#define INTERFACE_CONFIG_A_SDO_ACTIVE ((1 << 4) | (1 << 3))
|
|
||||||
|
|
||||||
#define LD_WRK_REGS_LDRX_OVERRIDE (1 << 0)
|
|
||||||
#define LD_WRK_REGS_LDTX_OVERRIDE (1 << 1)
|
|
||||||
|
|
||||||
#define RX_ENABLES_TX_VGA_EN (1 << 0)
|
|
||||||
#define RX_ENABLES_TX_VM_EN (1 << 1)
|
|
||||||
#define RX_ENABLES_TX_DRV_EN (1 << 2)
|
|
||||||
#define RX_ENABLES_CH3_TX_EN (1 << 3)
|
|
||||||
#define RX_ENABLES_CH2_TX_EN (1 << 4)
|
|
||||||
#define RX_ENABLES_CH1_TX_EN (1 << 5)
|
|
||||||
#define RX_ENABLES_CH0_TX_EN (1 << 6)
|
|
||||||
|
|
||||||
#define TX_ENABLES_TX_VGA_EN (1 << 0)
|
|
||||||
#define TX_ENABLES_TX_VM_EN (1 << 1)
|
|
||||||
#define TX_ENABLES_TX_DRV_EN (1 << 2)
|
|
||||||
#define TX_ENABLES_CH3_TX_EN (1 << 3)
|
|
||||||
#define TX_ENABLES_CH2_TX_EN (1 << 4)
|
|
||||||
#define TX_ENABLES_CH1_TX_EN (1 << 5)
|
|
||||||
#define TX_ENABLES_CH0_TX_EN (1 << 6)
|
|
||||||
|
|
||||||
#define MISC_ENABLES_CH4_DET_EN (1 << 0)
|
|
||||||
#define MISC_ENABLES_CH3_DET_EN (1 << 1)
|
|
||||||
#define MISC_ENABLES_CH2_DET_EN (1 << 2)
|
|
||||||
#define MISC_ENABLES_CH1_DET_EN (1 << 3)
|
|
||||||
#define MISC_ENABLES_LNA_BIAS_OUT_EN (1 << 4)
|
|
||||||
#define MISC_ENABLES_BIAS_EN (1 << 5)
|
|
||||||
#define MISC_ENABLES_BIAS_CTRL (1 << 6)
|
|
||||||
#define MISC_ENABLES_SW_DRV_TR_MODE_SEL (1 << 7)
|
|
||||||
|
|
||||||
#define SW_CTRL_POL (1 << 0)
|
|
||||||
#define SW_CTRL_TR_SPI (1 << 1)
|
|
||||||
#define SW_CTRL_TR_SOURCE (1 << 2)
|
|
||||||
#define SW_CTRL_SW_DRV_EN_POL (1 << 3)
|
|
||||||
#define SW_CTRL_SW_DRV_EN_TR (1 << 4)
|
|
||||||
#define SW_CTRL_RX_EN (1 << 5)
|
|
||||||
#define SW_CTRL_TX_EN (1 << 6)
|
|
||||||
#define SW_CTRL_SW_DRV_TR_STATE (1 << 7)
|
|
||||||
|
|
||||||
#define MEM_CTRL_RX_CHX_RAM_BYPASS (1 << 0)
|
|
||||||
#define MEM_CTRL_TX_CHX_RAM_BYPASS (1 << 1)
|
|
||||||
#define MEM_CTRL_RX_BEAM_STEP_EN (1 << 2)
|
|
||||||
#define MEM_CTRL_TX_BEAM_STEP_EN (1 << 3)
|
|
||||||
#define MEM_CTRL_BIAS_RAM_BYPASS (1 << 5)
|
|
||||||
#define MEM_CTRL_BEAM_RAM_BYPASS (1 << 6)
|
|
||||||
#define MEM_CTRL_SCAN_MODE_EN (1 << 7)
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
} // End extern "C"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif /* LIB_ADAR1000_H_ */
|
|
||||||
|
|
||||||
@@ -21,7 +21,6 @@
|
|||||||
#include "usb_device.h"
|
#include "usb_device.h"
|
||||||
#include "USBHandler.h"
|
#include "USBHandler.h"
|
||||||
#include "usbd_cdc_if.h"
|
#include "usbd_cdc_if.h"
|
||||||
#include "adar1000.h"
|
|
||||||
#include "ADAR1000_Manager.h"
|
#include "ADAR1000_Manager.h"
|
||||||
#include "ADAR1000_AGC.h"
|
#include "ADAR1000_AGC.h"
|
||||||
extern "C" {
|
extern "C" {
|
||||||
@@ -46,7 +45,9 @@ extern "C" {
|
|||||||
#include <vector>
|
#include <vector>
|
||||||
#include "stm32_spi.h"
|
#include "stm32_spi.h"
|
||||||
#include "stm32_delay.h"
|
#include "stm32_delay.h"
|
||||||
#include "TinyGPSPlus.h"
|
extern "C" {
|
||||||
|
#include "um982_gps.h"
|
||||||
|
}
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#include "GY_85_HAL.h"
|
#include "GY_85_HAL.h"
|
||||||
}
|
}
|
||||||
@@ -121,8 +122,8 @@ UART_HandleTypeDef huart5;
|
|||||||
UART_HandleTypeDef huart3;
|
UART_HandleTypeDef huart3;
|
||||||
|
|
||||||
/* USER CODE BEGIN PV */
|
/* USER CODE BEGIN PV */
|
||||||
// The TinyGPSPlus object
|
// UM982 dual-antenna GPS receiver
|
||||||
TinyGPSPlus gps;
|
UM982_GPS_t um982;
|
||||||
|
|
||||||
// Global data structures
|
// Global data structures
|
||||||
GPS_Data_t current_gps_data = {0};
|
GPS_Data_t current_gps_data = {0};
|
||||||
@@ -173,7 +174,7 @@ float RADAR_Altitude;
|
|||||||
double RADAR_Longitude = 0;
|
double RADAR_Longitude = 0;
|
||||||
double RADAR_Latitude = 0;
|
double RADAR_Latitude = 0;
|
||||||
|
|
||||||
extern uint8_t GUI_start_flag_received;
|
extern uint8_t GUI_start_flag_received; // [STM32-006] Legacy, unused -- kept for linker compat
|
||||||
|
|
||||||
|
|
||||||
//RADAR
|
//RADAR
|
||||||
@@ -620,7 +621,8 @@ typedef enum {
|
|||||||
ERROR_POWER_SUPPLY,
|
ERROR_POWER_SUPPLY,
|
||||||
ERROR_TEMPERATURE_HIGH,
|
ERROR_TEMPERATURE_HIGH,
|
||||||
ERROR_MEMORY_ALLOC,
|
ERROR_MEMORY_ALLOC,
|
||||||
ERROR_WATCHDOG_TIMEOUT
|
ERROR_WATCHDOG_TIMEOUT,
|
||||||
|
ERROR_COUNT // must be last — used for bounds checking error_strings[]
|
||||||
} SystemError_t;
|
} SystemError_t;
|
||||||
|
|
||||||
static SystemError_t last_error = ERROR_NONE;
|
static SystemError_t last_error = ERROR_NONE;
|
||||||
@@ -631,21 +633,42 @@ static bool system_emergency_state = false;
|
|||||||
SystemError_t checkSystemHealth(void) {
|
SystemError_t checkSystemHealth(void) {
|
||||||
SystemError_t current_error = ERROR_NONE;
|
SystemError_t current_error = ERROR_NONE;
|
||||||
|
|
||||||
// 1. Check AD9523 Clock Generator
|
// 0. Watchdog: detect main-loop stall (checkSystemHealth not called for >60 s).
|
||||||
static uint32_t last_clock_check = 0;
|
// Timestamp is captured at function ENTRY and updated unconditionally, so
|
||||||
if (HAL_GetTick() - last_clock_check > 5000) {
|
// any early return from a sub-check below cannot leave a stale value that
|
||||||
GPIO_PinState s0 = HAL_GPIO_ReadPin(AD9523_STATUS0_GPIO_Port, AD9523_STATUS0_Pin);
|
// would later trip a spurious ERROR_WATCHDOG_TIMEOUT. A dedicated cold-start
|
||||||
GPIO_PinState s1 = HAL_GPIO_ReadPin(AD9523_STATUS1_GPIO_Port, AD9523_STATUS1_Pin);
|
// branch ensures the first call after boot never trips (last_health_check==0
|
||||||
DIAG_GPIO("CLK", "AD9523 STATUS0", s0);
|
// would otherwise make `HAL_GetTick() - 0 > 60000` true forever after the
|
||||||
DIAG_GPIO("CLK", "AD9523 STATUS1", s1);
|
// 60-s mark of the init sequence).
|
||||||
if (s0 == GPIO_PIN_RESET || s1 == GPIO_PIN_RESET) {
|
static uint32_t last_health_check = 0;
|
||||||
current_error = ERROR_AD9523_CLOCK;
|
uint32_t now_tick = HAL_GetTick();
|
||||||
DIAG_ERR("CLK", "AD9523 clock health check FAILED (STATUS0=%d STATUS1=%d)", s0, s1);
|
if (last_health_check == 0) {
|
||||||
|
last_health_check = now_tick; // cold start: seed only
|
||||||
|
} else {
|
||||||
|
uint32_t elapsed = now_tick - last_health_check;
|
||||||
|
last_health_check = now_tick; // update BEFORE any early return
|
||||||
|
if (elapsed > 60000) {
|
||||||
|
current_error = ERROR_WATCHDOG_TIMEOUT;
|
||||||
|
DIAG_ERR("SYS", "Health check: Watchdog timeout (>60s since last check)");
|
||||||
return current_error;
|
return current_error;
|
||||||
}
|
}
|
||||||
last_clock_check = HAL_GetTick();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 1. Check AD9523 Clock Generator
|
||||||
|
static uint32_t last_clock_check = 0;
|
||||||
|
if (HAL_GetTick() - last_clock_check > 5000) {
|
||||||
|
GPIO_PinState s0 = HAL_GPIO_ReadPin(AD9523_STATUS0_GPIO_Port, AD9523_STATUS0_Pin);
|
||||||
|
GPIO_PinState s1 = HAL_GPIO_ReadPin(AD9523_STATUS1_GPIO_Port, AD9523_STATUS1_Pin);
|
||||||
|
DIAG_GPIO("CLK", "AD9523 STATUS0", s0);
|
||||||
|
DIAG_GPIO("CLK", "AD9523 STATUS1", s1);
|
||||||
|
if (s0 == GPIO_PIN_RESET || s1 == GPIO_PIN_RESET) {
|
||||||
|
current_error = ERROR_AD9523_CLOCK;
|
||||||
|
DIAG_ERR("CLK", "AD9523 clock health check FAILED (STATUS0=%d STATUS1=%d)", s0, s1);
|
||||||
|
return current_error;
|
||||||
|
}
|
||||||
|
last_clock_check = HAL_GetTick();
|
||||||
|
}
|
||||||
|
|
||||||
// 2. Check ADF4382 Lock Status
|
// 2. Check ADF4382 Lock Status
|
||||||
bool tx_locked, rx_locked;
|
bool tx_locked, rx_locked;
|
||||||
if (ADF4382A_CheckLockStatus(&lo_manager, &tx_locked, &rx_locked) == ADF4382A_MANAGER_OK) {
|
if (ADF4382A_CheckLockStatus(&lo_manager, &tx_locked, &rx_locked) == ADF4382A_MANAGER_OK) {
|
||||||
@@ -679,37 +702,34 @@ SystemError_t checkSystemHealth(void) {
|
|||||||
|
|
||||||
// 4. Check IMU Communication
|
// 4. Check IMU Communication
|
||||||
static uint32_t last_imu_check = 0;
|
static uint32_t last_imu_check = 0;
|
||||||
if (HAL_GetTick() - last_imu_check > 10000) {
|
if (HAL_GetTick() - last_imu_check > 10000) {
|
||||||
if (!GY85_Update(&imu)) {
|
if (!GY85_Update(&imu)) {
|
||||||
current_error = ERROR_IMU_COMM;
|
current_error = ERROR_IMU_COMM;
|
||||||
DIAG_ERR("IMU", "Health check: GY85_Update() FAILED");
|
DIAG_ERR("IMU", "Health check: GY85_Update() FAILED");
|
||||||
return current_error;
|
return current_error;
|
||||||
}
|
}
|
||||||
last_imu_check = HAL_GetTick();
|
last_imu_check = HAL_GetTick();
|
||||||
}
|
}
|
||||||
|
|
||||||
// 5. Check BMP180 Communication
|
// 5. Check BMP180 Communication
|
||||||
static uint32_t last_bmp_check = 0;
|
static uint32_t last_bmp_check = 0;
|
||||||
if (HAL_GetTick() - last_bmp_check > 15000) {
|
if (HAL_GetTick() - last_bmp_check > 15000) {
|
||||||
double pressure = myBMP.getPressure();
|
double pressure = myBMP.getPressure();
|
||||||
if (pressure < 30000.0 || pressure > 110000.0 || isnan(pressure)) {
|
if (pressure < 30000.0 || pressure > 110000.0 || isnan(pressure)) {
|
||||||
current_error = ERROR_BMP180_COMM;
|
current_error = ERROR_BMP180_COMM;
|
||||||
DIAG_ERR("SYS", "Health check: BMP180 pressure out of range: %.0f", pressure);
|
DIAG_ERR("SYS", "Health check: BMP180 pressure out of range: %.0f", pressure);
|
||||||
return current_error;
|
return current_error;
|
||||||
}
|
}
|
||||||
last_bmp_check = HAL_GetTick();
|
last_bmp_check = HAL_GetTick();
|
||||||
}
|
}
|
||||||
|
|
||||||
// 6. Check GPS Communication
|
// 6. Check GPS Communication (30s grace period from boot / last valid fix)
|
||||||
static uint32_t last_gps_fix = 0;
|
uint32_t gps_fix_age = um982_position_age(&um982);
|
||||||
if (gps.location.isUpdated()) {
|
if (gps_fix_age > 30000) {
|
||||||
last_gps_fix = HAL_GetTick();
|
current_error = ERROR_GPS_COMM;
|
||||||
}
|
DIAG_WARN("SYS", "Health check: GPS no fix for >30s (age=%lu ms)", (unsigned long)gps_fix_age);
|
||||||
if (HAL_GetTick() - last_gps_fix > 30000) {
|
return current_error;
|
||||||
current_error = ERROR_GPS_COMM;
|
}
|
||||||
DIAG_WARN("SYS", "Health check: GPS no fix for >30s");
|
|
||||||
return current_error;
|
|
||||||
}
|
|
||||||
|
|
||||||
// 7. Check RF Power Amplifier Current
|
// 7. Check RF Power Amplifier Current
|
||||||
if (PowerAmplifier) {
|
if (PowerAmplifier) {
|
||||||
@@ -734,14 +754,7 @@ SystemError_t checkSystemHealth(void) {
|
|||||||
return current_error;
|
return current_error;
|
||||||
}
|
}
|
||||||
|
|
||||||
// 9. Simple watchdog check
|
// 9. Watchdog check is performed at function entry (see step 0).
|
||||||
static uint32_t last_health_check = 0;
|
|
||||||
if (HAL_GetTick() - last_health_check > 60000) {
|
|
||||||
current_error = ERROR_WATCHDOG_TIMEOUT;
|
|
||||||
DIAG_ERR("SYS", "Health check: Watchdog timeout (>60s since last check)");
|
|
||||||
return current_error;
|
|
||||||
}
|
|
||||||
last_health_check = HAL_GetTick();
|
|
||||||
|
|
||||||
if (current_error != ERROR_NONE) {
|
if (current_error != ERROR_NONE) {
|
||||||
DIAG_ERR("SYS", "checkSystemHealth returning error code %d", current_error);
|
DIAG_ERR("SYS", "checkSystemHealth returning error code %d", current_error);
|
||||||
@@ -853,7 +866,7 @@ void handleSystemError(SystemError_t error) {
|
|||||||
DIAG_ERR("SYS", "handleSystemError: error=%d error_count=%lu", error, error_count);
|
DIAG_ERR("SYS", "handleSystemError: error=%d error_count=%lu", error, error_count);
|
||||||
|
|
||||||
char error_msg[100];
|
char error_msg[100];
|
||||||
const char* error_strings[] = {
|
static const char* const error_strings[] = {
|
||||||
"No error",
|
"No error",
|
||||||
"AD9523 Clock failure",
|
"AD9523 Clock failure",
|
||||||
"ADF4382 TX LO unlocked",
|
"ADF4382 TX LO unlocked",
|
||||||
@@ -873,9 +886,16 @@ void handleSystemError(SystemError_t error) {
|
|||||||
"Watchdog timeout"
|
"Watchdog timeout"
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static_assert(sizeof(error_strings) / sizeof(error_strings[0]) == ERROR_COUNT,
|
||||||
|
"error_strings[] and SystemError_t enum are out of sync");
|
||||||
|
|
||||||
|
const char* err_name = (error >= 0 && error < (int)(sizeof(error_strings) / sizeof(error_strings[0])))
|
||||||
|
? error_strings[error]
|
||||||
|
: "Unknown error";
|
||||||
|
|
||||||
snprintf(error_msg, sizeof(error_msg),
|
snprintf(error_msg, sizeof(error_msg),
|
||||||
"ERROR #%d: %s (Count: %lu)\r\n",
|
"ERROR #%d: %s (Count: %lu)\r\n",
|
||||||
error, error_strings[error], error_count);
|
error, err_name, error_count);
|
||||||
HAL_UART_Transmit(&huart3, (uint8_t*)error_msg, strlen(error_msg), 1000);
|
HAL_UART_Transmit(&huart3, (uint8_t*)error_msg, strlen(error_msg), 1000);
|
||||||
|
|
||||||
// Blink LED pattern based on error code
|
// Blink LED pattern based on error code
|
||||||
@@ -885,9 +905,23 @@ void handleSystemError(SystemError_t error) {
|
|||||||
HAL_Delay(200);
|
HAL_Delay(200);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Critical errors trigger emergency shutdown
|
// Critical errors trigger emergency shutdown.
|
||||||
if (error >= ERROR_RF_PA_OVERCURRENT && error <= ERROR_POWER_SUPPLY) {
|
//
|
||||||
DIAG_ERR("SYS", "CRITICAL ERROR (code %d: %s) -- initiating Emergency_Stop()", error, error_strings[error]);
|
// Safety-critical range: any fault that can damage the PAs or leave the
|
||||||
|
// system in an undefined state must cut the RF rails via Emergency_Stop().
|
||||||
|
// This covers:
|
||||||
|
// ERROR_RF_PA_OVERCURRENT .. ERROR_POWER_SUPPLY (9..13) -- PA/supply faults
|
||||||
|
// ERROR_TEMPERATURE_HIGH (14) -- >75 C on the PA thermal sensors;
|
||||||
|
// without cutting bias + 5V/5V5/RFPA rails
|
||||||
|
// the GaN QPA2962 stage can thermal-runaway.
|
||||||
|
// ERROR_WATCHDOG_TIMEOUT (16) -- health-check loop has stalled (>60 s);
|
||||||
|
// transmitter state is unknown, safest to
|
||||||
|
// latch Emergency_Stop rather than rely on
|
||||||
|
// IWDG reset (which re-energises the rails).
|
||||||
|
if ((error >= ERROR_RF_PA_OVERCURRENT && error <= ERROR_POWER_SUPPLY) ||
|
||||||
|
error == ERROR_TEMPERATURE_HIGH ||
|
||||||
|
error == ERROR_WATCHDOG_TIMEOUT) {
|
||||||
|
DIAG_ERR("SYS", "CRITICAL ERROR (code %d: %s) -- initiating Emergency_Stop()", error, err_name);
|
||||||
snprintf(error_msg, sizeof(error_msg),
|
snprintf(error_msg, sizeof(error_msg),
|
||||||
"CRITICAL ERROR! Initiating emergency shutdown.\r\n");
|
"CRITICAL ERROR! Initiating emergency shutdown.\r\n");
|
||||||
HAL_UART_Transmit(&huart3, (uint8_t*)error_msg, strlen(error_msg), 1000);
|
HAL_UART_Transmit(&huart3, (uint8_t*)error_msg, strlen(error_msg), 1000);
|
||||||
@@ -1020,20 +1054,7 @@ static inline void delay_ms(uint32_t ms) { HAL_Delay(ms); }
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
// This custom version of delay() ensures that the gps object
|
// smartDelay removed -- replaced by non-blocking um982_process() in main loop
|
||||||
// is being "fed".
|
|
||||||
static void smartDelay(unsigned long ms)
|
|
||||||
{
|
|
||||||
uint32_t start = HAL_GetTick();
|
|
||||||
uint8_t ch;
|
|
||||||
|
|
||||||
do {
|
|
||||||
// While there is new data available in UART (non-blocking)
|
|
||||||
if (HAL_UART_Receive(&huart5, &ch, 1, 0) == HAL_OK) {
|
|
||||||
gps.encode(ch); // Pass received byte to TinyGPS++ equivalent parser
|
|
||||||
}
|
|
||||||
} while (HAL_GetTick() - start < ms);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Small helper to enable DWT cycle counter for microdelay
|
// Small helper to enable DWT cycle counter for microdelay
|
||||||
static void DWT_Init(void)
|
static void DWT_Init(void)
|
||||||
@@ -1177,7 +1198,14 @@ static int configure_ad9523(void)
|
|||||||
|
|
||||||
// init ad9523 defaults (fills any missing pdata defaults)
|
// init ad9523 defaults (fills any missing pdata defaults)
|
||||||
DIAG("CLK", "Calling ad9523_init() -- fills pdata defaults");
|
DIAG("CLK", "Calling ad9523_init() -- fills pdata defaults");
|
||||||
ad9523_init(&init_param);
|
{
|
||||||
|
int32_t init_ret = ad9523_init(&init_param);
|
||||||
|
DIAG("CLK", "ad9523_init() returned %ld", (long)init_ret);
|
||||||
|
if (init_ret != 0) {
|
||||||
|
DIAG_ERR("CLK", "ad9523_init() FAILED (ret=%ld)", (long)init_ret);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/* [Bug #2 FIXED] Removed first ad9523_setup() call that was here.
|
/* [Bug #2 FIXED] Removed first ad9523_setup() call that was here.
|
||||||
* It wrote to the chip while still in reset — writes were lost.
|
* It wrote to the chip while still in reset — writes were lost.
|
||||||
@@ -1566,6 +1594,12 @@ int main(void)
|
|||||||
Yaw_Sensor = (180*atan2(magRawY,magRawX)/PI) - Mag_Declination;
|
Yaw_Sensor = (180*atan2(magRawY,magRawX)/PI) - Mag_Declination;
|
||||||
|
|
||||||
if(Yaw_Sensor<0)Yaw_Sensor+=360;
|
if(Yaw_Sensor<0)Yaw_Sensor+=360;
|
||||||
|
|
||||||
|
// Override magnetometer heading with UM982 dual-antenna heading when available
|
||||||
|
if (um982_is_heading_valid(&um982)) {
|
||||||
|
Yaw_Sensor = um982_get_heading(&um982);
|
||||||
|
}
|
||||||
|
|
||||||
RxEst_0 = RxEst_1;
|
RxEst_0 = RxEst_1;
|
||||||
RyEst_0 = RyEst_1;
|
RyEst_0 = RyEst_1;
|
||||||
RzEst_0 = RzEst_1;
|
RzEst_0 = RzEst_1;
|
||||||
@@ -1741,14 +1775,38 @@ int main(void)
|
|||||||
//////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////GPS/////////////////////////////////////////
|
//////////////////////////////////////////GPS/////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
for(int i=0; i<10;i++){
|
DIAG_SECTION("GPS INIT (UM982)");
|
||||||
smartDelay(1000);
|
DIAG("GPS", "Initializing UM982 on UART5 @ 115200 (baseline=50cm, tol=3cm)");
|
||||||
RADAR_Longitude = gps.location.lng();
|
if (!um982_init(&um982, &huart5, 50.0f, 3.0f)) {
|
||||||
RADAR_Latitude = gps.location.lat();
|
DIAG_WARN("GPS", "UM982 init: no VERSIONA response -- module may need more time");
|
||||||
|
// Not fatal: module may still start sending NMEA data after boot
|
||||||
|
} else {
|
||||||
|
DIAG("GPS", "UM982 init OK -- VERSIONA received");
|
||||||
}
|
}
|
||||||
|
|
||||||
//move Stepper to position 1 = 0°
|
// Collect GPS data for a few seconds (non-blocking pump)
|
||||||
HAL_GPIO_WritePin(STEPPER_CW_P_GPIO_Port, STEPPER_CW_P_Pin, GPIO_PIN_RESET);//Set stepper motor spinning direction to CCW
|
DIAG("GPS", "Pumping GPS for 5 seconds to acquire initial fix...");
|
||||||
|
{
|
||||||
|
uint32_t gps_start = HAL_GetTick();
|
||||||
|
while (HAL_GetTick() - gps_start < 5000) {
|
||||||
|
um982_process(&um982);
|
||||||
|
HAL_Delay(10);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
RADAR_Longitude = um982_get_longitude(&um982);
|
||||||
|
RADAR_Latitude = um982_get_latitude(&um982);
|
||||||
|
DIAG("GPS", "Initial position: lat=%.6f lon=%.6f fix=%d sats=%d",
|
||||||
|
RADAR_Latitude, RADAR_Longitude,
|
||||||
|
um982_get_fix_quality(&um982), um982_get_num_sats(&um982));
|
||||||
|
|
||||||
|
// Re-apply heading after GPS init so the north-alignment stepper move uses
|
||||||
|
// UM982 dual-antenna heading when available.
|
||||||
|
if (um982_is_heading_valid(&um982)) {
|
||||||
|
Yaw_Sensor = um982_get_heading(&um982);
|
||||||
|
}
|
||||||
|
|
||||||
|
//move Stepper to position 1 = 0°
|
||||||
|
HAL_GPIO_WritePin(STEPPER_CW_P_GPIO_Port, STEPPER_CW_P_Pin, GPIO_PIN_RESET);//Set stepper motor spinning direction to CCW
|
||||||
//Point Stepper to North
|
//Point Stepper to North
|
||||||
for(int i= 0;i<(int)(Yaw_Sensor*Stepper_steps/360);i++){
|
for(int i= 0;i<(int)(Yaw_Sensor*Stepper_steps/360);i++){
|
||||||
HAL_GPIO_WritePin(STEPPER_CLK_P_GPIO_Port, STEPPER_CLK_P_Pin, GPIO_PIN_SET);
|
HAL_GPIO_WritePin(STEPPER_CLK_P_GPIO_Port, STEPPER_CLK_P_Pin, GPIO_PIN_SET);
|
||||||
@@ -1770,29 +1828,11 @@ int main(void)
|
|||||||
HAL_UART_Transmit(&huart3, (uint8_t*)gps_send_error, sizeof(gps_send_error) - 1, 1000);
|
HAL_UART_Transmit(&huart3, (uint8_t*)gps_send_error, sizeof(gps_send_error) - 1, 1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check if start flag was received and settings are ready
|
/* [STM32-006 FIXED] Removed blocking do-while loop that waited for
|
||||||
do{
|
* usbHandler.isStartFlagReceived(). The production V7 PyQt GUI does not
|
||||||
if (usbHandler.isStartFlagReceived() &&
|
* send the legacy 4-byte start flag [23,46,158,237], so this loop hung
|
||||||
usbHandler.getState() == USBHandler::USBState::READY_FOR_DATA) {
|
* the MCU at boot indefinitely. The USB settings handshake (if ever
|
||||||
|
* re-enabled) should be handled non-blocking in the main loop. */
|
||||||
const RadarSettings& settings = usbHandler.getSettings();
|
|
||||||
|
|
||||||
// Use the settings to configure your radar system
|
|
||||||
/*
|
|
||||||
settings.getSystemFrequency();
|
|
||||||
settings.getChirpDuration1();
|
|
||||||
settings.getChirpDuration2();
|
|
||||||
settings.getChirpsPerPosition();
|
|
||||||
settings.getFreqMin();
|
|
||||||
settings.getFreqMax();
|
|
||||||
settings.getPRF1();
|
|
||||||
settings.getPRF2();
|
|
||||||
settings.getMaxDistance();
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
}while(!usbHandler.isStartFlagReceived());
|
|
||||||
|
|
||||||
/***************************************************************/
|
/***************************************************************/
|
||||||
/************RF Power Amplifier Powering up sequence************/
|
/************RF Power Amplifier Powering up sequence************/
|
||||||
@@ -2017,6 +2057,18 @@ int main(void)
|
|||||||
}
|
}
|
||||||
DIAG("SYS", "Exited safe mode blink loop -- system_emergency_state cleared");
|
DIAG("SYS", "Exited safe mode blink loop -- system_emergency_state cleared");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
////////////////////////// GPS: Non-blocking NMEA processing ////////////////////////
|
||||||
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
um982_process(&um982);
|
||||||
|
|
||||||
|
// Update position globals continuously
|
||||||
|
if (um982_is_position_valid(&um982)) {
|
||||||
|
RADAR_Latitude = um982_get_latitude(&um982);
|
||||||
|
RADAR_Longitude = um982_get_longitude(&um982);
|
||||||
|
}
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
////////////////////////// Monitor ADF4382A lock status periodically//////////////////
|
////////////////////////// Monitor ADF4382A lock status periodically//////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
@@ -2127,9 +2179,24 @@ int main(void)
|
|||||||
|
|
||||||
runRadarPulseSequence();
|
runRadarPulseSequence();
|
||||||
|
|
||||||
/* [AGC] Outer-loop AGC: read FPGA saturation flag (DIG_5 / PD13),
|
/* [AGC] Outer-loop AGC: sync enable from FPGA via DIG_6 (PD14),
|
||||||
* adjust ADAR1000 VGA common gain once per radar frame (~258 ms).
|
* then read saturation flag (DIG_5 / PD13) and adjust ADAR1000 VGA
|
||||||
* Only run when AGC is enabled — otherwise leave VGA gains untouched. */
|
* common gain once per radar frame (~258 ms).
|
||||||
|
* FPGA register host_agc_enable is the single source of truth —
|
||||||
|
* DIG_6 propagates it to MCU every frame.
|
||||||
|
* 2-frame confirmation debounce: only change outerAgc.enabled when
|
||||||
|
* two consecutive frames read the same DIG_6 value. Prevents a
|
||||||
|
* single-sample glitch from causing a spurious AGC state transition.
|
||||||
|
* Added latency: 1 extra frame (~258 ms), acceptable for control plane. */
|
||||||
|
{
|
||||||
|
bool dig6_now = (HAL_GPIO_ReadPin(FPGA_DIG6_GPIO_Port,
|
||||||
|
FPGA_DIG6_Pin) == GPIO_PIN_SET);
|
||||||
|
static bool dig6_prev = false; // matches boot default (AGC off)
|
||||||
|
if (dig6_now == dig6_prev) {
|
||||||
|
outerAgc.enabled = dig6_now;
|
||||||
|
}
|
||||||
|
dig6_prev = dig6_now;
|
||||||
|
}
|
||||||
if (outerAgc.enabled) {
|
if (outerAgc.enabled) {
|
||||||
bool sat = HAL_GPIO_ReadPin(FPGA_DIG5_SAT_GPIO_Port,
|
bool sat = HAL_GPIO_ReadPin(FPGA_DIG5_SAT_GPIO_Port,
|
||||||
FPGA_DIG5_SAT_Pin) == GPIO_PIN_SET;
|
FPGA_DIG5_SAT_Pin) == GPIO_PIN_SET;
|
||||||
@@ -2567,7 +2634,7 @@ static void MX_UART5_Init(void)
|
|||||||
|
|
||||||
/* USER CODE END UART5_Init 1 */
|
/* USER CODE END UART5_Init 1 */
|
||||||
huart5.Instance = UART5;
|
huart5.Instance = UART5;
|
||||||
huart5.Init.BaudRate = 9600;
|
huart5.Init.BaudRate = 115200;
|
||||||
huart5.Init.WordLength = UART_WORDLENGTH_8B;
|
huart5.Init.WordLength = UART_WORDLENGTH_8B;
|
||||||
huart5.Init.StopBits = UART_STOPBITS_1;
|
huart5.Init.StopBits = UART_STOPBITS_1;
|
||||||
huart5.Init.Parity = UART_PARITY_NONE;
|
huart5.Init.Parity = UART_PARITY_NONE;
|
||||||
|
|||||||
@@ -0,0 +1,586 @@
|
|||||||
|
/*******************************************************************************
|
||||||
|
* um982_gps.c -- UM982 dual-antenna GNSS receiver driver implementation
|
||||||
|
*
|
||||||
|
* See um982_gps.h for API documentation.
|
||||||
|
* Command syntax per Unicore N4 Command Reference EN R1.14.
|
||||||
|
******************************************************************************/
|
||||||
|
#include "um982_gps.h"
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
/* ========================= Internal helpers ========================== */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Advance to the next comma-delimited field in an NMEA sentence.
|
||||||
|
* Returns pointer to the start of the next field (after the comma),
|
||||||
|
* or NULL if no more commas found before end-of-string or '*'.
|
||||||
|
*
|
||||||
|
* Handles empty fields (consecutive commas) correctly by returning
|
||||||
|
* a pointer to the character after the comma (which may be another comma).
|
||||||
|
*/
|
||||||
|
static const char *next_field(const char *p)
|
||||||
|
{
|
||||||
|
if (p == NULL) return NULL;
|
||||||
|
while (*p != '\0' && *p != ',' && *p != '*') {
|
||||||
|
p++;
|
||||||
|
}
|
||||||
|
if (*p == ',') return p + 1;
|
||||||
|
return NULL; /* End of sentence or checksum marker */
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get the length of the current field (up to next comma, '*', or '\0').
|
||||||
|
*/
|
||||||
|
static int field_len(const char *p)
|
||||||
|
{
|
||||||
|
int len = 0;
|
||||||
|
if (p == NULL) return 0;
|
||||||
|
while (p[len] != '\0' && p[len] != ',' && p[len] != '*') {
|
||||||
|
len++;
|
||||||
|
}
|
||||||
|
return len;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if a field is non-empty (has at least one character before delimiter).
|
||||||
|
*/
|
||||||
|
static bool field_valid(const char *p)
|
||||||
|
{
|
||||||
|
return p != NULL && field_len(p) > 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse a floating-point value from a field, returning 0.0 if empty.
|
||||||
|
*/
|
||||||
|
static double field_to_double(const char *p)
|
||||||
|
{
|
||||||
|
if (!field_valid(p)) return 0.0;
|
||||||
|
return strtod(p, NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static float field_to_float(const char *p)
|
||||||
|
{
|
||||||
|
return (float)field_to_double(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
static int field_to_int(const char *p)
|
||||||
|
{
|
||||||
|
if (!field_valid(p)) return 0;
|
||||||
|
return (int)strtol(p, NULL, 10);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Checksum ================================== */
|
||||||
|
|
||||||
|
bool um982_verify_checksum(const char *sentence)
|
||||||
|
{
|
||||||
|
if (sentence == NULL || sentence[0] != '$') return false;
|
||||||
|
|
||||||
|
const char *p = sentence + 1; /* Skip '$' */
|
||||||
|
uint8_t computed = 0;
|
||||||
|
|
||||||
|
while (*p != '\0' && *p != '*') {
|
||||||
|
computed ^= (uint8_t)*p;
|
||||||
|
p++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (*p != '*') return false; /* No checksum marker found */
|
||||||
|
p++; /* Skip '*' */
|
||||||
|
|
||||||
|
/* Parse 2-char hex checksum */
|
||||||
|
if (p[0] == '\0' || p[1] == '\0') return false;
|
||||||
|
|
||||||
|
char hex_str[3] = { p[0], p[1], '\0' };
|
||||||
|
unsigned long expected = strtoul(hex_str, NULL, 16);
|
||||||
|
|
||||||
|
return computed == (uint8_t)expected;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Coordinate parsing ======================== */
|
||||||
|
|
||||||
|
double um982_parse_coord(const char *field, char hemisphere)
|
||||||
|
{
|
||||||
|
if (field == NULL || field[0] == '\0') return NAN;
|
||||||
|
|
||||||
|
/* Find the decimal point to determine degree digit count.
|
||||||
|
* Latitude: ddmm.mmmm (dot at index 4, degrees = 2)
|
||||||
|
* Longitude: dddmm.mmmm (dot at index 5, degrees = 3)
|
||||||
|
* General: degree_digits = dot_position - 2
|
||||||
|
*/
|
||||||
|
const char *dot = strchr(field, '.');
|
||||||
|
if (dot == NULL) return NAN;
|
||||||
|
|
||||||
|
int dot_pos = (int)(dot - field);
|
||||||
|
int deg_digits = dot_pos - 2;
|
||||||
|
|
||||||
|
if (deg_digits < 1 || deg_digits > 3) return NAN;
|
||||||
|
|
||||||
|
/* Extract degree portion */
|
||||||
|
double degrees = 0.0;
|
||||||
|
for (int i = 0; i < deg_digits; i++) {
|
||||||
|
if (field[i] < '0' || field[i] > '9') return NAN;
|
||||||
|
degrees = degrees * 10.0 + (field[i] - '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Extract minutes portion (everything from deg_digits onward) */
|
||||||
|
double minutes = strtod(field + deg_digits, NULL);
|
||||||
|
if (minutes < 0.0 || minutes >= 60.0) return NAN;
|
||||||
|
|
||||||
|
double result = degrees + minutes / 60.0;
|
||||||
|
|
||||||
|
/* Apply hemisphere sign */
|
||||||
|
if (hemisphere == 'S' || hemisphere == 'W') {
|
||||||
|
result = -result;
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Sentence parsers ========================== */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Identify the NMEA sentence type by skipping the 2-char talker ID
|
||||||
|
* and comparing the 3-letter formatter.
|
||||||
|
*
|
||||||
|
* "$GNGGA,..." -> talker="GN", formatter="GGA"
|
||||||
|
* "$GPTHS,..." -> talker="GP", formatter="THS"
|
||||||
|
*
|
||||||
|
* Returns pointer to the formatter (3 chars at sentence+3), or NULL
|
||||||
|
* if sentence is too short.
|
||||||
|
*/
|
||||||
|
static const char *get_formatter(const char *sentence)
|
||||||
|
{
|
||||||
|
/* sentence starts with '$', followed by 2-char talker + 3-char formatter */
|
||||||
|
if (sentence == NULL || strlen(sentence) < 6) return NULL;
|
||||||
|
return sentence + 3; /* Skip "$XX" -> points to formatter */
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse GGA sentence — position and fix quality.
|
||||||
|
*
|
||||||
|
* Format: $--GGA,time,lat,N/S,lon,E/W,quality,numSat,hdop,alt,M,geoidSep,M,dgpsAge,refID*XX
|
||||||
|
* field: 1 2 3 4 5 6 7 8 9 10 11 12 13 14
|
||||||
|
*/
|
||||||
|
static void parse_gga(UM982_GPS_t *gps, const char *sentence)
|
||||||
|
{
|
||||||
|
/* Skip to first field (after "$XXGGA,") */
|
||||||
|
const char *f = strchr(sentence, ',');
|
||||||
|
if (f == NULL) return;
|
||||||
|
f++; /* f -> field 1 (time) */
|
||||||
|
|
||||||
|
/* Field 1: UTC time — skip for now */
|
||||||
|
const char *f2 = next_field(f); /* lat */
|
||||||
|
const char *f3 = next_field(f2); /* N/S */
|
||||||
|
const char *f4 = next_field(f3); /* lon */
|
||||||
|
const char *f5 = next_field(f4); /* E/W */
|
||||||
|
const char *f6 = next_field(f5); /* quality */
|
||||||
|
const char *f7 = next_field(f6); /* numSat */
|
||||||
|
const char *f8 = next_field(f7); /* hdop */
|
||||||
|
const char *f9 = next_field(f8); /* altitude */
|
||||||
|
const char *f10 = next_field(f9); /* M */
|
||||||
|
const char *f11 = next_field(f10); /* geoid sep */
|
||||||
|
|
||||||
|
uint32_t now = HAL_GetTick();
|
||||||
|
|
||||||
|
/* Parse fix quality first — if 0, position is meaningless */
|
||||||
|
gps->fix_quality = (uint8_t)field_to_int(f6);
|
||||||
|
|
||||||
|
/* Parse coordinates */
|
||||||
|
if (field_valid(f2) && field_valid(f3)) {
|
||||||
|
char hem = field_valid(f3) ? *f3 : 'N';
|
||||||
|
double lat = um982_parse_coord(f2, hem);
|
||||||
|
if (!isnan(lat)) gps->latitude = lat;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (field_valid(f4) && field_valid(f5)) {
|
||||||
|
char hem = field_valid(f5) ? *f5 : 'E';
|
||||||
|
double lon = um982_parse_coord(f4, hem);
|
||||||
|
if (!isnan(lon)) gps->longitude = lon;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Number of satellites */
|
||||||
|
gps->num_satellites = (uint8_t)field_to_int(f7);
|
||||||
|
|
||||||
|
/* HDOP */
|
||||||
|
if (field_valid(f8)) {
|
||||||
|
gps->hdop = field_to_float(f8);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Altitude */
|
||||||
|
if (field_valid(f9)) {
|
||||||
|
gps->altitude = field_to_float(f9);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Geoid separation */
|
||||||
|
if (field_valid(f11)) {
|
||||||
|
gps->geoid_sep = field_to_float(f11);
|
||||||
|
}
|
||||||
|
|
||||||
|
gps->last_gga_tick = now;
|
||||||
|
if (gps->fix_quality != UM982_FIX_NONE) {
|
||||||
|
gps->last_fix_tick = now;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse RMC sentence — recommended minimum (position, speed, date).
|
||||||
|
*
|
||||||
|
* Format: $--RMC,time,status,lat,N/S,lon,E/W,speed,course,date,magVar,E/W,mode*XX
|
||||||
|
* field: 1 2 3 4 5 6 7 8 9 10 11 12
|
||||||
|
*/
|
||||||
|
static void parse_rmc(UM982_GPS_t *gps, const char *sentence)
|
||||||
|
{
|
||||||
|
const char *f = strchr(sentence, ',');
|
||||||
|
if (f == NULL) return;
|
||||||
|
f++; /* f -> field 1 (time) */
|
||||||
|
|
||||||
|
const char *f2 = next_field(f); /* status */
|
||||||
|
const char *f3 = next_field(f2); /* lat */
|
||||||
|
const char *f4 = next_field(f3); /* N/S */
|
||||||
|
const char *f5 = next_field(f4); /* lon */
|
||||||
|
const char *f6 = next_field(f5); /* E/W */
|
||||||
|
const char *f7 = next_field(f6); /* speed knots */
|
||||||
|
const char *f8 = next_field(f7); /* course true */
|
||||||
|
|
||||||
|
/* Status */
|
||||||
|
if (field_valid(f2)) {
|
||||||
|
gps->rmc_status = *f2;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Position (only if status = A for valid) */
|
||||||
|
if (field_valid(f2) && *f2 == 'A') {
|
||||||
|
if (field_valid(f3) && field_valid(f4)) {
|
||||||
|
double lat = um982_parse_coord(f3, *f4);
|
||||||
|
if (!isnan(lat)) gps->latitude = lat;
|
||||||
|
}
|
||||||
|
if (field_valid(f5) && field_valid(f6)) {
|
||||||
|
double lon = um982_parse_coord(f5, *f6);
|
||||||
|
if (!isnan(lon)) gps->longitude = lon;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Speed (knots) */
|
||||||
|
if (field_valid(f7)) {
|
||||||
|
gps->speed_knots = field_to_float(f7);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Course */
|
||||||
|
if (field_valid(f8)) {
|
||||||
|
gps->course_true = field_to_float(f8);
|
||||||
|
}
|
||||||
|
|
||||||
|
gps->last_rmc_tick = HAL_GetTick();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse THS sentence — true heading and status (UM982-specific).
|
||||||
|
*
|
||||||
|
* Format: $--THS,heading,mode*XX
|
||||||
|
* field: 1 2
|
||||||
|
*/
|
||||||
|
static void parse_ths(UM982_GPS_t *gps, const char *sentence)
|
||||||
|
{
|
||||||
|
const char *f = strchr(sentence, ',');
|
||||||
|
if (f == NULL) return;
|
||||||
|
f++; /* f -> field 1 (heading) */
|
||||||
|
|
||||||
|
const char *f2 = next_field(f); /* mode */
|
||||||
|
|
||||||
|
/* Heading */
|
||||||
|
if (field_valid(f)) {
|
||||||
|
gps->heading = field_to_float(f);
|
||||||
|
} else {
|
||||||
|
gps->heading = NAN;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Mode */
|
||||||
|
if (field_valid(f2)) {
|
||||||
|
gps->heading_mode = *f2;
|
||||||
|
} else {
|
||||||
|
gps->heading_mode = 'V'; /* Not valid if missing */
|
||||||
|
}
|
||||||
|
|
||||||
|
gps->last_ths_tick = HAL_GetTick();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse VTG sentence — course and speed over ground.
|
||||||
|
*
|
||||||
|
* Format: $--VTG,courseTrue,T,courseMag,M,speedKnots,N,speedKmh,K,mode*XX
|
||||||
|
* field: 1 2 3 4 5 6 7 8 9
|
||||||
|
*/
|
||||||
|
static void parse_vtg(UM982_GPS_t *gps, const char *sentence)
|
||||||
|
{
|
||||||
|
const char *f = strchr(sentence, ',');
|
||||||
|
if (f == NULL) return;
|
||||||
|
f++; /* f -> field 1 (course true) */
|
||||||
|
|
||||||
|
const char *f2 = next_field(f); /* T */
|
||||||
|
const char *f3 = next_field(f2); /* course mag */
|
||||||
|
const char *f4 = next_field(f3); /* M */
|
||||||
|
const char *f5 = next_field(f4); /* speed knots */
|
||||||
|
const char *f6 = next_field(f5); /* N */
|
||||||
|
const char *f7 = next_field(f6); /* speed km/h */
|
||||||
|
|
||||||
|
/* Course true */
|
||||||
|
if (field_valid(f)) {
|
||||||
|
gps->course_true = field_to_float(f);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Speed knots */
|
||||||
|
if (field_valid(f5)) {
|
||||||
|
gps->speed_knots = field_to_float(f5);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Speed km/h */
|
||||||
|
if (field_valid(f7)) {
|
||||||
|
gps->speed_kmh = field_to_float(f7);
|
||||||
|
}
|
||||||
|
|
||||||
|
gps->last_vtg_tick = HAL_GetTick();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Sentence dispatch ========================= */
|
||||||
|
|
||||||
|
void um982_parse_sentence(UM982_GPS_t *gps, const char *sentence)
|
||||||
|
{
|
||||||
|
if (sentence == NULL || sentence[0] != '$') return;
|
||||||
|
|
||||||
|
/* Verify checksum before parsing */
|
||||||
|
if (!um982_verify_checksum(sentence)) return;
|
||||||
|
|
||||||
|
/* Check for VERSIONA response (starts with '#', not '$') -- handled separately */
|
||||||
|
/* Actually VERSIONA starts with '#', so it won't enter here. We check in feed(). */
|
||||||
|
|
||||||
|
/* Identify sentence type */
|
||||||
|
const char *fmt = get_formatter(sentence);
|
||||||
|
if (fmt == NULL) return;
|
||||||
|
|
||||||
|
if (strncmp(fmt, "GGA", 3) == 0) {
|
||||||
|
gps->initialized = true;
|
||||||
|
parse_gga(gps, sentence);
|
||||||
|
} else if (strncmp(fmt, "RMC", 3) == 0) {
|
||||||
|
gps->initialized = true;
|
||||||
|
parse_rmc(gps, sentence);
|
||||||
|
} else if (strncmp(fmt, "THS", 3) == 0) {
|
||||||
|
gps->initialized = true;
|
||||||
|
parse_ths(gps, sentence);
|
||||||
|
} else if (strncmp(fmt, "VTG", 3) == 0) {
|
||||||
|
gps->initialized = true;
|
||||||
|
parse_vtg(gps, sentence);
|
||||||
|
}
|
||||||
|
/* Other sentences silently ignored */
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Command interface ========================= */
|
||||||
|
|
||||||
|
bool um982_send_command(UM982_GPS_t *gps, const char *cmd)
|
||||||
|
{
|
||||||
|
if (gps == NULL || gps->huart == NULL || cmd == NULL) return false;
|
||||||
|
|
||||||
|
/* Build command with \r\n termination */
|
||||||
|
char buf[UM982_CMD_BUF_SIZE];
|
||||||
|
int len = snprintf(buf, sizeof(buf), "%s\r\n", cmd);
|
||||||
|
if (len <= 0 || (size_t)len >= sizeof(buf)) return false;
|
||||||
|
|
||||||
|
HAL_StatusTypeDef status = HAL_UART_Transmit(
|
||||||
|
gps->huart, (const uint8_t *)buf, (uint16_t)len, 100);
|
||||||
|
|
||||||
|
return status == HAL_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Line assembly + feed ====================== */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Process a completed line from the line buffer.
|
||||||
|
*/
|
||||||
|
static void process_line(UM982_GPS_t *gps, const char *line)
|
||||||
|
{
|
||||||
|
if (line == NULL || line[0] == '\0') return;
|
||||||
|
|
||||||
|
/* NMEA sentence starts with '$' */
|
||||||
|
if (line[0] == '$') {
|
||||||
|
um982_parse_sentence(gps, line);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Unicore proprietary response starts with '#' (e.g. #VERSIONA) */
|
||||||
|
if (line[0] == '#') {
|
||||||
|
if (strncmp(line + 1, "VERSIONA", 8) == 0) {
|
||||||
|
gps->version_received = true;
|
||||||
|
gps->initialized = true;
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void um982_feed(UM982_GPS_t *gps, const uint8_t *data, uint16_t len)
|
||||||
|
{
|
||||||
|
if (gps == NULL || data == NULL || len == 0) return;
|
||||||
|
|
||||||
|
for (uint16_t i = 0; i < len; i++) {
|
||||||
|
uint8_t ch = data[i];
|
||||||
|
|
||||||
|
/* End of line: process if we have content */
|
||||||
|
if (ch == '\n' || ch == '\r') {
|
||||||
|
if (gps->line_len > 0 && !gps->line_overflow) {
|
||||||
|
gps->line_buf[gps->line_len] = '\0';
|
||||||
|
process_line(gps, gps->line_buf);
|
||||||
|
}
|
||||||
|
gps->line_len = 0;
|
||||||
|
gps->line_overflow = false;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Accumulate into line buffer */
|
||||||
|
if (gps->line_len < UM982_LINE_BUF_SIZE - 1) {
|
||||||
|
gps->line_buf[gps->line_len++] = (char)ch;
|
||||||
|
} else {
|
||||||
|
gps->line_overflow = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= UART process (production) ================= */
|
||||||
|
|
||||||
|
void um982_process(UM982_GPS_t *gps)
|
||||||
|
{
|
||||||
|
if (gps == NULL || gps->huart == NULL) return;
|
||||||
|
|
||||||
|
/* Read all available bytes from the UART one at a time.
|
||||||
|
* At 115200 baud (~11.5 KB/s) and a typical main-loop period of ~10 ms,
|
||||||
|
* we expect ~115 bytes per call — negligible overhead on a 168 MHz STM32.
|
||||||
|
*
|
||||||
|
* Note: batch reads (HAL_UART_Receive with Size > 1 and Timeout = 0) are
|
||||||
|
* NOT safe here because the HAL consumes bytes from the data register as
|
||||||
|
* it reads them. If fewer than Size bytes are available, the consumed
|
||||||
|
* bytes are lost (HAL_TIMEOUT is returned and the caller has no way to
|
||||||
|
* know how many bytes were actually placed into the buffer). */
|
||||||
|
uint8_t ch;
|
||||||
|
while (HAL_UART_Receive(gps->huart, &ch, 1, 0) == HAL_OK) {
|
||||||
|
um982_feed(gps, &ch, 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Validity checks =========================== */
|
||||||
|
|
||||||
|
bool um982_is_heading_valid(const UM982_GPS_t *gps)
|
||||||
|
{
|
||||||
|
if (gps == NULL) return false;
|
||||||
|
if (isnan(gps->heading)) return false;
|
||||||
|
|
||||||
|
/* Mode must be Autonomous or Differential */
|
||||||
|
if (gps->heading_mode != 'A' && gps->heading_mode != 'D') return false;
|
||||||
|
|
||||||
|
/* Check age */
|
||||||
|
uint32_t age = HAL_GetTick() - gps->last_ths_tick;
|
||||||
|
return age < UM982_HEADING_TIMEOUT_MS;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool um982_is_position_valid(const UM982_GPS_t *gps)
|
||||||
|
{
|
||||||
|
if (gps == NULL) return false;
|
||||||
|
if (gps->fix_quality == UM982_FIX_NONE) return false;
|
||||||
|
|
||||||
|
/* Check age of the last valid fix */
|
||||||
|
uint32_t age = HAL_GetTick() - gps->last_fix_tick;
|
||||||
|
return age < UM982_POSITION_TIMEOUT_MS;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t um982_heading_age(const UM982_GPS_t *gps)
|
||||||
|
{
|
||||||
|
if (gps == NULL) return UINT32_MAX;
|
||||||
|
return HAL_GetTick() - gps->last_ths_tick;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t um982_position_age(const UM982_GPS_t *gps)
|
||||||
|
{
|
||||||
|
if (gps == NULL) return UINT32_MAX;
|
||||||
|
return HAL_GetTick() - gps->last_fix_tick;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Initialization ============================ */
|
||||||
|
|
||||||
|
bool um982_init(UM982_GPS_t *gps, UART_HandleTypeDef *huart,
|
||||||
|
float baseline_cm, float tolerance_cm)
|
||||||
|
{
|
||||||
|
if (gps == NULL || huart == NULL) return false;
|
||||||
|
|
||||||
|
/* Zero-init entire structure */
|
||||||
|
memset(gps, 0, sizeof(UM982_GPS_t));
|
||||||
|
|
||||||
|
gps->huart = huart;
|
||||||
|
gps->heading = NAN;
|
||||||
|
gps->heading_mode = 'V';
|
||||||
|
gps->rmc_status = 'V';
|
||||||
|
gps->speed_knots = 0.0f;
|
||||||
|
|
||||||
|
/* Seed fix timestamp so position_age() returns ~0 instead of uptime.
|
||||||
|
* Gives the module a full 30s grace window from init to acquire a fix
|
||||||
|
* before the health check fires ERROR_GPS_COMM. */
|
||||||
|
gps->last_fix_tick = HAL_GetTick();
|
||||||
|
gps->speed_kmh = 0.0f;
|
||||||
|
gps->course_true = 0.0f;
|
||||||
|
|
||||||
|
/* Step 1: Stop all current output to get a clean slate */
|
||||||
|
um982_send_command(gps, "UNLOG");
|
||||||
|
HAL_Delay(100);
|
||||||
|
|
||||||
|
/* Step 2: Configure heading mode
|
||||||
|
* Per N4 Reference 4.18: CONFIG HEADING FIXLENGTH (default mode)
|
||||||
|
* "The distance between ANT1 and ANT2 is fixed. They move synchronously." */
|
||||||
|
um982_send_command(gps, "CONFIG HEADING FIXLENGTH");
|
||||||
|
HAL_Delay(50);
|
||||||
|
|
||||||
|
/* Step 3: Set baseline length if specified
|
||||||
|
* Per N4 Reference: CONFIG HEADING LENGTH <cm> <tolerance_cm>
|
||||||
|
* "parameter1: Fixed baseline length (cm), valid range >= 0"
|
||||||
|
* "parameter2: Tolerable error margin (cm), valid range > 0" */
|
||||||
|
if (baseline_cm > 0.0f) {
|
||||||
|
char cmd[64];
|
||||||
|
if (tolerance_cm > 0.0f) {
|
||||||
|
snprintf(cmd, sizeof(cmd), "CONFIG HEADING LENGTH %.0f %.0f",
|
||||||
|
baseline_cm, tolerance_cm);
|
||||||
|
} else {
|
||||||
|
snprintf(cmd, sizeof(cmd), "CONFIG HEADING LENGTH %.0f",
|
||||||
|
baseline_cm);
|
||||||
|
}
|
||||||
|
um982_send_command(gps, cmd);
|
||||||
|
HAL_Delay(50);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Step 4: Enable NMEA output sentences on COM2.
|
||||||
|
* Per N4 Reference: "When requesting NMEA messages, users should add GP
|
||||||
|
* before each command name"
|
||||||
|
*
|
||||||
|
* We target COM2 because the ELT0213 board (GNSS.STORE) exposes COM2
|
||||||
|
* (RXD2/TXD2) on its 12-pin JST connector (pins 5 & 6). The STM32
|
||||||
|
* UART5 (PC12-TX, PD2-RX) connects to these pins via JP8.
|
||||||
|
* COM2 defaults to 115200 baud — matching our UART5 config. */
|
||||||
|
um982_send_command(gps, "GPGGA COM2 1"); /* GGA at 1 Hz */
|
||||||
|
HAL_Delay(50);
|
||||||
|
um982_send_command(gps, "GPRMC COM2 1"); /* RMC at 1 Hz */
|
||||||
|
HAL_Delay(50);
|
||||||
|
um982_send_command(gps, "GPTHS COM2 0.2"); /* THS at 5 Hz (heading primary) */
|
||||||
|
HAL_Delay(50);
|
||||||
|
|
||||||
|
/* Step 5: Skip SAVECONFIG -- NMEA config is re-sent every boot anyway.
|
||||||
|
* Saving to NVM on every power cycle would wear flash. If persistent
|
||||||
|
* config is needed, call um982_send_command(gps, "SAVECONFIG") once
|
||||||
|
* during commissioning. */
|
||||||
|
|
||||||
|
/* Step 6: Query version to verify communication */
|
||||||
|
gps->version_received = false;
|
||||||
|
um982_send_command(gps, "VERSIONA");
|
||||||
|
|
||||||
|
/* Wait for VERSIONA response (non-blocking poll) */
|
||||||
|
uint32_t start = HAL_GetTick();
|
||||||
|
while (!gps->version_received &&
|
||||||
|
(HAL_GetTick() - start) < UM982_INIT_TIMEOUT_MS) {
|
||||||
|
um982_process(gps);
|
||||||
|
HAL_Delay(10);
|
||||||
|
}
|
||||||
|
|
||||||
|
gps->initialized = gps->version_received;
|
||||||
|
return gps->initialized;
|
||||||
|
}
|
||||||
@@ -0,0 +1,213 @@
|
|||||||
|
/*******************************************************************************
|
||||||
|
* um982_gps.h -- UM982 dual-antenna GNSS receiver driver
|
||||||
|
*
|
||||||
|
* Parses NMEA sentences (GGA, RMC, THS, VTG) from the Unicore UM982 module
|
||||||
|
* and provides position, heading, and velocity data.
|
||||||
|
*
|
||||||
|
* Design principles:
|
||||||
|
* - Non-blocking: process() reads available UART bytes without waiting
|
||||||
|
* - Correct NMEA parsing: proper tokenizer handles empty fields
|
||||||
|
* - Longitude handles 3-digit degrees (dddmm.mmmm) via decimal-point detection
|
||||||
|
* - Checksum verified on every sentence
|
||||||
|
* - Command syntax verified against Unicore N4 Command Reference EN R1.14
|
||||||
|
*
|
||||||
|
* Hardware: UM982 on UART5 @ 115200 baud, dual-antenna heading mode
|
||||||
|
******************************************************************************/
|
||||||
|
#ifndef UM982_GPS_H
|
||||||
|
#define UM982_GPS_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Forward-declare the HAL UART handle type. The real definition comes from
|
||||||
|
* stm32f7xx_hal.h (production) or stm32_hal_mock.h (tests). */
|
||||||
|
#ifndef STM32_HAL_MOCK_H
|
||||||
|
#include "stm32f7xx_hal.h"
|
||||||
|
#else
|
||||||
|
/* Already included via mock -- nothing to do */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* ========================= Constants ================================= */
|
||||||
|
|
||||||
|
#define UM982_RX_BUF_SIZE 512 /* Ring buffer for incoming UART bytes */
|
||||||
|
#define UM982_LINE_BUF_SIZE 96 /* Max NMEA sentence (82 chars + margin) */
|
||||||
|
#define UM982_CMD_BUF_SIZE 128 /* Outgoing command buffer */
|
||||||
|
#define UM982_INIT_TIMEOUT_MS 3000 /* Timeout waiting for VERSIONA response */
|
||||||
|
|
||||||
|
/* Fix quality values (from GGA field 6) */
|
||||||
|
#define UM982_FIX_NONE 0
|
||||||
|
#define UM982_FIX_GPS 1
|
||||||
|
#define UM982_FIX_DGPS 2
|
||||||
|
#define UM982_FIX_RTK_FIXED 4
|
||||||
|
#define UM982_FIX_RTK_FLOAT 5
|
||||||
|
|
||||||
|
/* Validity timeout defaults (ms) */
|
||||||
|
#define UM982_HEADING_TIMEOUT_MS 2000
|
||||||
|
#define UM982_POSITION_TIMEOUT_MS 5000
|
||||||
|
|
||||||
|
/* ========================= Data Types ================================ */
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
/* Position */
|
||||||
|
double latitude; /* Decimal degrees, positive = North */
|
||||||
|
double longitude; /* Decimal degrees, positive = East */
|
||||||
|
float altitude; /* Meters above MSL */
|
||||||
|
float geoid_sep; /* Geoid separation (meters) */
|
||||||
|
|
||||||
|
/* Heading (from dual-antenna THS) */
|
||||||
|
float heading; /* True heading 0-360 degrees, NAN if invalid */
|
||||||
|
char heading_mode; /* A=autonomous, D=diff, E=est, M=manual, S=sim, V=invalid */
|
||||||
|
|
||||||
|
/* Velocity */
|
||||||
|
float speed_knots; /* Speed over ground (knots) */
|
||||||
|
float speed_kmh; /* Speed over ground (km/h) */
|
||||||
|
float course_true; /* Course over ground (degrees true) */
|
||||||
|
|
||||||
|
/* Quality */
|
||||||
|
uint8_t fix_quality; /* 0=none, 1=GPS, 2=DGPS, 4=RTK fixed, 5=RTK float */
|
||||||
|
uint8_t num_satellites; /* Satellites used in fix */
|
||||||
|
float hdop; /* Horizontal dilution of precision */
|
||||||
|
|
||||||
|
/* RMC status */
|
||||||
|
char rmc_status; /* A=valid, V=warning */
|
||||||
|
|
||||||
|
/* Timestamps (HAL_GetTick() at last update) */
|
||||||
|
uint32_t last_fix_tick; /* Last valid GGA fix (fix_quality > 0) */
|
||||||
|
uint32_t last_gga_tick;
|
||||||
|
uint32_t last_rmc_tick;
|
||||||
|
uint32_t last_ths_tick;
|
||||||
|
uint32_t last_vtg_tick;
|
||||||
|
|
||||||
|
/* Communication state */
|
||||||
|
bool initialized; /* VERSIONA or supported NMEA traffic seen */
|
||||||
|
bool version_received; /* VERSIONA response seen */
|
||||||
|
|
||||||
|
/* ---- Internal parser state (not for external use) ---- */
|
||||||
|
|
||||||
|
/* Ring buffer */
|
||||||
|
uint8_t rx_buf[UM982_RX_BUF_SIZE];
|
||||||
|
uint16_t rx_head; /* Write index */
|
||||||
|
uint16_t rx_tail; /* Read index */
|
||||||
|
|
||||||
|
/* Line assembler */
|
||||||
|
char line_buf[UM982_LINE_BUF_SIZE];
|
||||||
|
uint8_t line_len;
|
||||||
|
bool line_overflow; /* Current line exceeded buffer */
|
||||||
|
|
||||||
|
/* UART handle */
|
||||||
|
UART_HandleTypeDef *huart;
|
||||||
|
|
||||||
|
} UM982_GPS_t;
|
||||||
|
|
||||||
|
/* ========================= Public API ================================ */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Initialize the UM982_GPS_t structure and configure the module.
|
||||||
|
*
|
||||||
|
* Sends: UNLOG, CONFIG HEADING, optional CONFIG HEADING LENGTH,
|
||||||
|
* GPGGA, GPRMC, GPTHS
|
||||||
|
* Queries VERSIONA to verify communication.
|
||||||
|
*
|
||||||
|
* @param gps Pointer to UM982_GPS_t instance
|
||||||
|
* @param huart UART handle (e.g. &huart5)
|
||||||
|
* @param baseline_cm Distance between antennas in cm (0 = use module default)
|
||||||
|
* @param tolerance_cm Baseline tolerance in cm (0 = use module default)
|
||||||
|
* @return true if VERSIONA response received within timeout
|
||||||
|
*/
|
||||||
|
bool um982_init(UM982_GPS_t *gps, UART_HandleTypeDef *huart,
|
||||||
|
float baseline_cm, float tolerance_cm);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Process available UART data. Call from main loop — non-blocking.
|
||||||
|
*
|
||||||
|
* Reads all available bytes from UART, assembles lines, and dispatches
|
||||||
|
* complete NMEA sentences to the appropriate parser.
|
||||||
|
*
|
||||||
|
* @param gps Pointer to UM982_GPS_t instance
|
||||||
|
*/
|
||||||
|
void um982_process(UM982_GPS_t *gps);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Feed raw bytes directly into the parser (useful for testing).
|
||||||
|
* In production, um982_process() calls this internally after UART read.
|
||||||
|
*
|
||||||
|
* @param gps Pointer to UM982_GPS_t instance
|
||||||
|
* @param data Pointer to byte array
|
||||||
|
* @param len Number of bytes
|
||||||
|
*/
|
||||||
|
void um982_feed(UM982_GPS_t *gps, const uint8_t *data, uint16_t len);
|
||||||
|
|
||||||
|
/* ---- Getters ---- */
|
||||||
|
|
||||||
|
static inline float um982_get_heading(const UM982_GPS_t *gps) { return gps->heading; }
|
||||||
|
static inline double um982_get_latitude(const UM982_GPS_t *gps) { return gps->latitude; }
|
||||||
|
static inline double um982_get_longitude(const UM982_GPS_t *gps) { return gps->longitude; }
|
||||||
|
static inline float um982_get_altitude(const UM982_GPS_t *gps) { return gps->altitude; }
|
||||||
|
static inline uint8_t um982_get_fix_quality(const UM982_GPS_t *gps) { return gps->fix_quality; }
|
||||||
|
static inline uint8_t um982_get_num_sats(const UM982_GPS_t *gps) { return gps->num_satellites; }
|
||||||
|
static inline float um982_get_hdop(const UM982_GPS_t *gps) { return gps->hdop; }
|
||||||
|
static inline float um982_get_speed_knots(const UM982_GPS_t *gps) { return gps->speed_knots; }
|
||||||
|
static inline float um982_get_speed_kmh(const UM982_GPS_t *gps) { return gps->speed_kmh; }
|
||||||
|
static inline float um982_get_course(const UM982_GPS_t *gps) { return gps->course_true; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if heading is valid (mode A or D, and within timeout).
|
||||||
|
*/
|
||||||
|
bool um982_is_heading_valid(const UM982_GPS_t *gps);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Check if position is valid (fix_quality > 0, and within timeout).
|
||||||
|
*/
|
||||||
|
bool um982_is_position_valid(const UM982_GPS_t *gps);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get age of last heading update in milliseconds.
|
||||||
|
*/
|
||||||
|
uint32_t um982_heading_age(const UM982_GPS_t *gps);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get age of the last valid position fix in milliseconds.
|
||||||
|
*/
|
||||||
|
uint32_t um982_position_age(const UM982_GPS_t *gps);
|
||||||
|
|
||||||
|
/* ========================= Internal (exposed for testing) ============ */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Verify NMEA checksum. Returns true if valid.
|
||||||
|
* Sentence must start with '$' and contain '*XX' before termination.
|
||||||
|
*/
|
||||||
|
bool um982_verify_checksum(const char *sentence);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse a complete NMEA line (with $ prefix and *XX checksum).
|
||||||
|
* Dispatches to GGA/RMC/THS/VTG parsers as appropriate.
|
||||||
|
*/
|
||||||
|
void um982_parse_sentence(UM982_GPS_t *gps, const char *sentence);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse NMEA coordinate string to decimal degrees.
|
||||||
|
* Works for both latitude (ddmm.mmmm) and longitude (dddmm.mmmm)
|
||||||
|
* by detecting the decimal point position.
|
||||||
|
*
|
||||||
|
* @param field NMEA coordinate field (e.g. "4404.14036" or "12118.85961")
|
||||||
|
* @param hemisphere 'N', 'S', 'E', or 'W'
|
||||||
|
* @return Decimal degrees (negative for S/W), or NAN on parse error
|
||||||
|
*/
|
||||||
|
double um982_parse_coord(const char *field, char hemisphere);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send a command to the UM982. Appends \r\n automatically.
|
||||||
|
* @return true if UART transmit succeeded
|
||||||
|
*/
|
||||||
|
bool um982_send_command(UM982_GPS_t *gps, const char *cmd);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* UM982_GPS_H */
|
||||||
@@ -3,18 +3,38 @@
|
|||||||
*.dSYM/
|
*.dSYM/
|
||||||
|
|
||||||
# Test binaries (built by Makefile)
|
# Test binaries (built by Makefile)
|
||||||
|
# TESTS_WITH_REAL
|
||||||
test_bug1_timed_sync_init_ordering
|
test_bug1_timed_sync_init_ordering
|
||||||
test_bug2_ad9523_double_setup
|
|
||||||
test_bug3_timed_sync_noop
|
test_bug3_timed_sync_noop
|
||||||
test_bug4_phase_shift_before_check
|
test_bug4_phase_shift_before_check
|
||||||
test_bug5_fine_phase_gpio_only
|
test_bug5_fine_phase_gpio_only
|
||||||
|
test_bug9_platform_ops_null
|
||||||
|
test_bug10_spi_cs_not_toggled
|
||||||
|
test_bug15_htim3_dangling_extern
|
||||||
|
|
||||||
|
# TESTS_MOCK_ONLY
|
||||||
|
test_bug2_ad9523_double_setup
|
||||||
test_bug6_timer_variable_collision
|
test_bug6_timer_variable_collision
|
||||||
test_bug7_gpio_pin_conflict
|
test_bug7_gpio_pin_conflict
|
||||||
test_bug8_uart_commented_out
|
test_bug8_uart_commented_out
|
||||||
test_bug9_platform_ops_null
|
test_bug14_diag_section_args
|
||||||
test_bug10_spi_cs_not_toggled
|
test_gap3_emergency_stop_rails
|
||||||
test_bug11_platform_spi_transmit_only
|
|
||||||
|
# TESTS_STANDALONE
|
||||||
test_bug12_pa_cal_loop_inverted
|
test_bug12_pa_cal_loop_inverted
|
||||||
test_bug13_dac2_adc_buffer_mismatch
|
test_bug13_dac2_adc_buffer_mismatch
|
||||||
test_bug14_diag_section_args
|
test_gap3_iwdg_config
|
||||||
test_bug15_htim3_dangling_extern
|
test_gap3_temperature_max
|
||||||
|
test_gap3_idq_periodic_reread
|
||||||
|
test_gap3_emergency_state_ordering
|
||||||
|
test_gap3_overtemp_emergency_stop
|
||||||
|
test_gap3_health_watchdog_cold_start
|
||||||
|
|
||||||
|
# TESTS_WITH_PLATFORM
|
||||||
|
test_bug11_platform_spi_transmit_only
|
||||||
|
|
||||||
|
# TESTS_WITH_CXX
|
||||||
|
test_agc_outer_loop
|
||||||
|
|
||||||
|
# Manual / one-off test builds
|
||||||
|
test_um982_gps
|
||||||
|
|||||||
@@ -27,6 +27,10 @@ CXX_LIB_DIR := ../9_1_1_C_Cpp_Libraries
|
|||||||
CXX_SRCS := $(CXX_LIB_DIR)/ADAR1000_AGC.cpp $(CXX_LIB_DIR)/ADAR1000_Manager.cpp
|
CXX_SRCS := $(CXX_LIB_DIR)/ADAR1000_AGC.cpp $(CXX_LIB_DIR)/ADAR1000_Manager.cpp
|
||||||
CXX_OBJS := ADAR1000_AGC.o ADAR1000_Manager.o
|
CXX_OBJS := ADAR1000_AGC.o ADAR1000_Manager.o
|
||||||
|
|
||||||
|
# GPS driver source
|
||||||
|
GPS_SRC := ../9_1_3_C_Cpp_Code/um982_gps.c
|
||||||
|
GPS_OBJ := um982_gps.o
|
||||||
|
|
||||||
# Real source files compiled against mock headers
|
# Real source files compiled against mock headers
|
||||||
REAL_SRC := ../9_1_1_C_Cpp_Libraries/adf4382a_manager.c
|
REAL_SRC := ../9_1_1_C_Cpp_Libraries/adf4382a_manager.c
|
||||||
|
|
||||||
@@ -64,7 +68,9 @@ TESTS_STANDALONE := test_bug12_pa_cal_loop_inverted \
|
|||||||
test_gap3_iwdg_config \
|
test_gap3_iwdg_config \
|
||||||
test_gap3_temperature_max \
|
test_gap3_temperature_max \
|
||||||
test_gap3_idq_periodic_reread \
|
test_gap3_idq_periodic_reread \
|
||||||
test_gap3_emergency_state_ordering
|
test_gap3_emergency_state_ordering \
|
||||||
|
test_gap3_overtemp_emergency_stop \
|
||||||
|
test_gap3_health_watchdog_cold_start
|
||||||
|
|
||||||
# Tests that need platform_noos_stm32.o + mocks
|
# Tests that need platform_noos_stm32.o + mocks
|
||||||
TESTS_WITH_PLATFORM := test_bug11_platform_spi_transmit_only
|
TESTS_WITH_PLATFORM := test_bug11_platform_spi_transmit_only
|
||||||
@@ -72,11 +78,15 @@ TESTS_WITH_PLATFORM := test_bug11_platform_spi_transmit_only
|
|||||||
# C++ tests (AGC outer loop)
|
# C++ tests (AGC outer loop)
|
||||||
TESTS_WITH_CXX := test_agc_outer_loop
|
TESTS_WITH_CXX := test_agc_outer_loop
|
||||||
|
|
||||||
ALL_TESTS := $(TESTS_WITH_REAL) $(TESTS_MOCK_ONLY) $(TESTS_STANDALONE) $(TESTS_WITH_PLATFORM) $(TESTS_WITH_CXX)
|
# GPS driver tests (need mocks + GPS source + -lm)
|
||||||
|
TESTS_GPS := test_um982_gps
|
||||||
|
|
||||||
|
ALL_TESTS := $(TESTS_WITH_REAL) $(TESTS_MOCK_ONLY) $(TESTS_STANDALONE) $(TESTS_WITH_PLATFORM) $(TESTS_WITH_CXX) $(TESTS_GPS)
|
||||||
|
|
||||||
.PHONY: all build test clean \
|
.PHONY: all build test clean \
|
||||||
$(addprefix test_,bug1 bug2 bug3 bug4 bug5 bug6 bug7 bug8 bug9 bug10 bug11 bug12 bug13 bug14 bug15) \
|
$(addprefix test_,bug1 bug2 bug3 bug4 bug5 bug6 bug7 bug8 bug9 bug10 bug11 bug12 bug13 bug14 bug15) \
|
||||||
test_gap3_estop test_gap3_iwdg test_gap3_temp test_gap3_idq test_gap3_order
|
test_gap3_estop test_gap3_iwdg test_gap3_temp test_gap3_idq test_gap3_order \
|
||||||
|
test_gap3_overtemp test_gap3_wdog
|
||||||
|
|
||||||
all: build test
|
all: build test
|
||||||
|
|
||||||
@@ -162,6 +172,12 @@ test_gap3_idq_periodic_reread: test_gap3_idq_periodic_reread.c
|
|||||||
test_gap3_emergency_state_ordering: test_gap3_emergency_state_ordering.c
|
test_gap3_emergency_state_ordering: test_gap3_emergency_state_ordering.c
|
||||||
$(CC) $(CFLAGS) $< -o $@
|
$(CC) $(CFLAGS) $< -o $@
|
||||||
|
|
||||||
|
test_gap3_overtemp_emergency_stop: test_gap3_overtemp_emergency_stop.c
|
||||||
|
$(CC) $(CFLAGS) $< -o $@
|
||||||
|
|
||||||
|
test_gap3_health_watchdog_cold_start: test_gap3_health_watchdog_cold_start.c
|
||||||
|
$(CC) $(CFLAGS) $< -o $@
|
||||||
|
|
||||||
# Tests that need platform_noos_stm32.o + mocks
|
# Tests that need platform_noos_stm32.o + mocks
|
||||||
$(TESTS_WITH_PLATFORM): %: %.c $(MOCK_OBJS) $(PLATFORM_OBJ)
|
$(TESTS_WITH_PLATFORM): %: %.c $(MOCK_OBJS) $(PLATFORM_OBJ)
|
||||||
$(CC) $(CFLAGS) $(INCLUDES) $< $(MOCK_OBJS) $(PLATFORM_OBJ) -o $@
|
$(CC) $(CFLAGS) $(INCLUDES) $< $(MOCK_OBJS) $(PLATFORM_OBJ) -o $@
|
||||||
@@ -184,6 +200,20 @@ test_agc_outer_loop: test_agc_outer_loop.cpp $(CXX_OBJS) $(MOCK_OBJS)
|
|||||||
test_agc: test_agc_outer_loop
|
test_agc: test_agc_outer_loop
|
||||||
./test_agc_outer_loop
|
./test_agc_outer_loop
|
||||||
|
|
||||||
|
# --- GPS driver rules ---
|
||||||
|
|
||||||
|
$(GPS_OBJ): $(GPS_SRC)
|
||||||
|
$(CC) $(CFLAGS) $(INCLUDES) -I../9_1_3_C_Cpp_Code -c $< -o $@
|
||||||
|
|
||||||
|
# Note: test includes um982_gps.c directly for white-box testing (static fn access)
|
||||||
|
test_um982_gps: test_um982_gps.c $(MOCK_OBJS)
|
||||||
|
$(CC) $(CFLAGS) $(INCLUDES) -I../9_1_3_C_Cpp_Code $< $(MOCK_OBJS) -lm -o $@
|
||||||
|
|
||||||
|
# Convenience target
|
||||||
|
.PHONY: test_gps
|
||||||
|
test_gps: test_um982_gps
|
||||||
|
./test_um982_gps
|
||||||
|
|
||||||
# --- Individual test targets ---
|
# --- Individual test targets ---
|
||||||
|
|
||||||
test_bug1: test_bug1_timed_sync_init_ordering
|
test_bug1: test_bug1_timed_sync_init_ordering
|
||||||
@@ -246,6 +276,12 @@ test_gap3_idq: test_gap3_idq_periodic_reread
|
|||||||
test_gap3_order: test_gap3_emergency_state_ordering
|
test_gap3_order: test_gap3_emergency_state_ordering
|
||||||
./test_gap3_emergency_state_ordering
|
./test_gap3_emergency_state_ordering
|
||||||
|
|
||||||
|
test_gap3_overtemp: test_gap3_overtemp_emergency_stop
|
||||||
|
./test_gap3_overtemp_emergency_stop
|
||||||
|
|
||||||
|
test_gap3_wdog: test_gap3_health_watchdog_cold_start
|
||||||
|
./test_gap3_health_watchdog_cold_start
|
||||||
|
|
||||||
# --- Clean ---
|
# --- Clean ---
|
||||||
|
|
||||||
clean:
|
clean:
|
||||||
|
|||||||
@@ -21,6 +21,7 @@ SPI_HandleTypeDef hspi4 = { .id = 4 };
|
|||||||
I2C_HandleTypeDef hi2c1 = { .id = 1 };
|
I2C_HandleTypeDef hi2c1 = { .id = 1 };
|
||||||
I2C_HandleTypeDef hi2c2 = { .id = 2 };
|
I2C_HandleTypeDef hi2c2 = { .id = 2 };
|
||||||
UART_HandleTypeDef huart3 = { .id = 3 };
|
UART_HandleTypeDef huart3 = { .id = 3 };
|
||||||
|
UART_HandleTypeDef huart5 = { .id = 5 }; /* GPS UART */
|
||||||
ADC_HandleTypeDef hadc3 = { .id = 3 };
|
ADC_HandleTypeDef hadc3 = { .id = 3 };
|
||||||
TIM_HandleTypeDef htim3 = { .id = 3 };
|
TIM_HandleTypeDef htim3 = { .id = 3 };
|
||||||
|
|
||||||
@@ -34,6 +35,26 @@ uint32_t mock_tick = 0;
|
|||||||
/* ========================= Printf control ========================= */
|
/* ========================= Printf control ========================= */
|
||||||
int mock_printf_enabled = 0;
|
int mock_printf_enabled = 0;
|
||||||
|
|
||||||
|
/* ========================= Mock UART TX capture =================== */
|
||||||
|
uint8_t mock_uart_tx_buf[MOCK_UART_TX_BUF_SIZE];
|
||||||
|
uint16_t mock_uart_tx_len = 0;
|
||||||
|
|
||||||
|
/* ========================= Mock UART RX buffer ==================== */
|
||||||
|
#define MOCK_UART_RX_SLOTS 8
|
||||||
|
|
||||||
|
static struct {
|
||||||
|
uint32_t uart_id;
|
||||||
|
uint8_t buf[MOCK_UART_RX_BUF_SIZE];
|
||||||
|
uint16_t head;
|
||||||
|
uint16_t tail;
|
||||||
|
} mock_uart_rx[MOCK_UART_RX_SLOTS];
|
||||||
|
|
||||||
|
void mock_uart_tx_clear(void)
|
||||||
|
{
|
||||||
|
mock_uart_tx_len = 0;
|
||||||
|
memset(mock_uart_tx_buf, 0, sizeof(mock_uart_tx_buf));
|
||||||
|
}
|
||||||
|
|
||||||
/* ========================= Mock GPIO read ========================= */
|
/* ========================= Mock GPIO read ========================= */
|
||||||
#define GPIO_READ_TABLE_SIZE 32
|
#define GPIO_READ_TABLE_SIZE 32
|
||||||
static struct {
|
static struct {
|
||||||
@@ -49,6 +70,9 @@ void spy_reset(void)
|
|||||||
mock_tick = 0;
|
mock_tick = 0;
|
||||||
mock_printf_enabled = 0;
|
mock_printf_enabled = 0;
|
||||||
memset(gpio_read_table, 0, sizeof(gpio_read_table));
|
memset(gpio_read_table, 0, sizeof(gpio_read_table));
|
||||||
|
memset(mock_uart_rx, 0, sizeof(mock_uart_rx));
|
||||||
|
mock_uart_tx_len = 0;
|
||||||
|
memset(mock_uart_tx_buf, 0, sizeof(mock_uart_tx_buf));
|
||||||
}
|
}
|
||||||
|
|
||||||
const SpyRecord *spy_get(int index)
|
const SpyRecord *spy_get(int index)
|
||||||
@@ -185,6 +209,83 @@ HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pD
|
|||||||
.value = Timeout,
|
.value = Timeout,
|
||||||
.extra = huart
|
.extra = huart
|
||||||
});
|
});
|
||||||
|
/* Capture TX data for test inspection */
|
||||||
|
for (uint16_t i = 0; i < Size && mock_uart_tx_len < MOCK_UART_TX_BUF_SIZE; i++) {
|
||||||
|
mock_uart_tx_buf[mock_uart_tx_len++] = pData[i];
|
||||||
|
}
|
||||||
|
return HAL_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Mock UART RX helpers ====================== */
|
||||||
|
|
||||||
|
/* find_rx_slot, mock_uart_rx_load, etc. use the mock_uart_rx declared above */
|
||||||
|
|
||||||
|
static int find_rx_slot(UART_HandleTypeDef *huart)
|
||||||
|
{
|
||||||
|
if (huart == NULL) return -1;
|
||||||
|
/* Find existing slot */
|
||||||
|
for (int i = 0; i < MOCK_UART_RX_SLOTS; i++) {
|
||||||
|
if (mock_uart_rx[i].uart_id == huart->id && mock_uart_rx[i].head != mock_uart_rx[i].tail) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
if (mock_uart_rx[i].uart_id == huart->id) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/* Find empty slot */
|
||||||
|
for (int i = 0; i < MOCK_UART_RX_SLOTS; i++) {
|
||||||
|
if (mock_uart_rx[i].uart_id == 0) {
|
||||||
|
mock_uart_rx[i].uart_id = huart->id;
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mock_uart_rx_load(UART_HandleTypeDef *huart, const uint8_t *data, uint16_t len)
|
||||||
|
{
|
||||||
|
int slot = find_rx_slot(huart);
|
||||||
|
if (slot < 0) return;
|
||||||
|
mock_uart_rx[slot].uart_id = huart->id;
|
||||||
|
for (uint16_t i = 0; i < len; i++) {
|
||||||
|
uint16_t next = (mock_uart_rx[slot].head + 1) % MOCK_UART_RX_BUF_SIZE;
|
||||||
|
if (next == mock_uart_rx[slot].tail) break; /* Buffer full */
|
||||||
|
mock_uart_rx[slot].buf[mock_uart_rx[slot].head] = data[i];
|
||||||
|
mock_uart_rx[slot].head = next;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void mock_uart_rx_clear(UART_HandleTypeDef *huart)
|
||||||
|
{
|
||||||
|
int slot = find_rx_slot(huart);
|
||||||
|
if (slot < 0) return;
|
||||||
|
mock_uart_rx[slot].head = 0;
|
||||||
|
mock_uart_rx[slot].tail = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData,
|
||||||
|
uint16_t Size, uint32_t Timeout)
|
||||||
|
{
|
||||||
|
(void)Timeout;
|
||||||
|
int slot = find_rx_slot(huart);
|
||||||
|
if (slot < 0) return HAL_TIMEOUT;
|
||||||
|
|
||||||
|
for (uint16_t i = 0; i < Size; i++) {
|
||||||
|
if (mock_uart_rx[slot].head == mock_uart_rx[slot].tail) {
|
||||||
|
return HAL_TIMEOUT; /* No more data */
|
||||||
|
}
|
||||||
|
pData[i] = mock_uart_rx[slot].buf[mock_uart_rx[slot].tail];
|
||||||
|
mock_uart_rx[slot].tail = (mock_uart_rx[slot].tail + 1) % MOCK_UART_RX_BUF_SIZE;
|
||||||
|
}
|
||||||
|
|
||||||
|
spy_push((SpyRecord){
|
||||||
|
.type = SPY_UART_RX,
|
||||||
|
.port = NULL,
|
||||||
|
.pin = Size,
|
||||||
|
.value = Timeout,
|
||||||
|
.extra = huart
|
||||||
|
});
|
||||||
|
|
||||||
return HAL_OK;
|
return HAL_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -105,6 +105,7 @@ typedef struct {
|
|||||||
extern SPI_HandleTypeDef hspi1, hspi4;
|
extern SPI_HandleTypeDef hspi1, hspi4;
|
||||||
extern I2C_HandleTypeDef hi2c1, hi2c2;
|
extern I2C_HandleTypeDef hi2c1, hi2c2;
|
||||||
extern UART_HandleTypeDef huart3;
|
extern UART_HandleTypeDef huart3;
|
||||||
|
extern UART_HandleTypeDef huart5; /* GPS UART */
|
||||||
extern ADC_HandleTypeDef hadc3;
|
extern ADC_HandleTypeDef hadc3;
|
||||||
extern TIM_HandleTypeDef htim3; /* Timer for DELADJ PWM */
|
extern TIM_HandleTypeDef htim3; /* Timer for DELADJ PWM */
|
||||||
|
|
||||||
@@ -139,6 +140,7 @@ typedef enum {
|
|||||||
SPY_TIM_SET_COMPARE,
|
SPY_TIM_SET_COMPARE,
|
||||||
SPY_SPI_TRANSMIT_RECEIVE,
|
SPY_SPI_TRANSMIT_RECEIVE,
|
||||||
SPY_SPI_TRANSMIT,
|
SPY_SPI_TRANSMIT,
|
||||||
|
SPY_UART_RX,
|
||||||
} SpyCallType;
|
} SpyCallType;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
@@ -187,6 +189,23 @@ void HAL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
|
|||||||
uint32_t HAL_GetTick(void);
|
uint32_t HAL_GetTick(void);
|
||||||
void HAL_Delay(uint32_t Delay);
|
void HAL_Delay(uint32_t Delay);
|
||||||
HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
||||||
|
HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
||||||
|
|
||||||
|
/* ========================= Mock UART RX buffer ======================= */
|
||||||
|
|
||||||
|
/* Inject bytes into the mock UART RX buffer for a specific UART handle.
|
||||||
|
* HAL_UART_Receive will return these bytes one at a time. */
|
||||||
|
#define MOCK_UART_RX_BUF_SIZE 2048
|
||||||
|
|
||||||
|
void mock_uart_rx_load(UART_HandleTypeDef *huart, const uint8_t *data, uint16_t len);
|
||||||
|
void mock_uart_rx_clear(UART_HandleTypeDef *huart);
|
||||||
|
|
||||||
|
/* Capture buffer for UART TX data (to verify commands sent to GPS module) */
|
||||||
|
#define MOCK_UART_TX_BUF_SIZE 2048
|
||||||
|
|
||||||
|
extern uint8_t mock_uart_tx_buf[MOCK_UART_TX_BUF_SIZE];
|
||||||
|
extern uint16_t mock_uart_tx_len;
|
||||||
|
void mock_uart_tx_clear(void);
|
||||||
|
|
||||||
/* ========================= SPI stubs ============================== */
|
/* ========================= SPI stubs ============================== */
|
||||||
|
|
||||||
|
|||||||
@@ -50,7 +50,7 @@ static void test_defaults()
|
|||||||
assert(agc.min_gain == 0);
|
assert(agc.min_gain == 0);
|
||||||
assert(agc.max_gain == 127);
|
assert(agc.max_gain == 127);
|
||||||
assert(agc.holdoff_frames == 4);
|
assert(agc.holdoff_frames == 4);
|
||||||
assert(agc.enabled == true);
|
assert(agc.enabled == false); // disabled by default — FPGA DIG_6 is source of truth
|
||||||
assert(agc.holdoff_counter == 0);
|
assert(agc.holdoff_counter == 0);
|
||||||
assert(agc.last_saturated == false);
|
assert(agc.last_saturated == false);
|
||||||
assert(agc.saturation_event_count == 0);
|
assert(agc.saturation_event_count == 0);
|
||||||
@@ -67,6 +67,7 @@ static void test_defaults()
|
|||||||
static void test_saturation_reduces_gain()
|
static void test_saturation_reduces_gain()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
uint8_t initial = agc.agc_base_gain; // 30
|
uint8_t initial = agc.agc_base_gain; // 30
|
||||||
|
|
||||||
agc.update(true); // saturation
|
agc.update(true); // saturation
|
||||||
@@ -82,6 +83,7 @@ static void test_saturation_reduces_gain()
|
|||||||
static void test_holdoff_prevents_early_gain_up()
|
static void test_holdoff_prevents_early_gain_up()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
agc.update(true); // saturate once -> gain = 26
|
agc.update(true); // saturate once -> gain = 26
|
||||||
uint8_t after_sat = agc.agc_base_gain;
|
uint8_t after_sat = agc.agc_base_gain;
|
||||||
|
|
||||||
@@ -101,6 +103,7 @@ static void test_holdoff_prevents_early_gain_up()
|
|||||||
static void test_recovery_after_holdoff()
|
static void test_recovery_after_holdoff()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
agc.update(true); // saturate -> gain = 26
|
agc.update(true); // saturate -> gain = 26
|
||||||
uint8_t after_sat = agc.agc_base_gain;
|
uint8_t after_sat = agc.agc_base_gain;
|
||||||
|
|
||||||
@@ -119,6 +122,7 @@ static void test_recovery_after_holdoff()
|
|||||||
static void test_min_gain_clamp()
|
static void test_min_gain_clamp()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
agc.min_gain = 10;
|
agc.min_gain = 10;
|
||||||
agc.agc_base_gain = 12;
|
agc.agc_base_gain = 12;
|
||||||
agc.gain_step_down = 4;
|
agc.gain_step_down = 4;
|
||||||
@@ -136,6 +140,7 @@ static void test_min_gain_clamp()
|
|||||||
static void test_max_gain_clamp()
|
static void test_max_gain_clamp()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
agc.max_gain = 32;
|
agc.max_gain = 32;
|
||||||
agc.agc_base_gain = 31;
|
agc.agc_base_gain = 31;
|
||||||
agc.gain_step_up = 2;
|
agc.gain_step_up = 2;
|
||||||
@@ -226,6 +231,7 @@ static void test_apply_gain_spi()
|
|||||||
static void test_reset_preserves_config()
|
static void test_reset_preserves_config()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
agc.agc_base_gain = 42;
|
agc.agc_base_gain = 42;
|
||||||
agc.gain_step_down = 8;
|
agc.gain_step_down = 8;
|
||||||
agc.cal_offset[3] = -5;
|
agc.cal_offset[3] = -5;
|
||||||
@@ -255,6 +261,7 @@ static void test_reset_preserves_config()
|
|||||||
static void test_saturation_counter()
|
static void test_saturation_counter()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
|
|
||||||
for (int i = 0; i < 10; ++i) {
|
for (int i = 0; i < 10; ++i) {
|
||||||
agc.update(true);
|
agc.update(true);
|
||||||
@@ -274,6 +281,7 @@ static void test_saturation_counter()
|
|||||||
static void test_mixed_sequence()
|
static void test_mixed_sequence()
|
||||||
{
|
{
|
||||||
ADAR1000_AGC agc;
|
ADAR1000_AGC agc;
|
||||||
|
agc.enabled = true; // default is OFF; enable for this test
|
||||||
agc.agc_base_gain = 30;
|
agc.agc_base_gain = 30;
|
||||||
agc.gain_step_down = 4;
|
agc.gain_step_down = 4;
|
||||||
agc.gain_step_up = 1;
|
agc.gain_step_up = 1;
|
||||||
|
|||||||
@@ -34,22 +34,25 @@ static void Mock_Emergency_Stop(void)
|
|||||||
state_was_true_when_estop_called = system_emergency_state;
|
state_was_true_when_estop_called = system_emergency_state;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Error codes (subset matching main.cpp) */
|
/* Error codes (subset matching main.cpp SystemError_t) */
|
||||||
typedef enum {
|
typedef enum {
|
||||||
ERROR_NONE = 0,
|
ERROR_NONE = 0,
|
||||||
ERROR_RF_PA_OVERCURRENT = 9,
|
ERROR_RF_PA_OVERCURRENT = 9,
|
||||||
ERROR_RF_PA_BIAS = 10,
|
ERROR_RF_PA_BIAS = 10,
|
||||||
ERROR_STEPPER_FAULT = 11,
|
ERROR_STEPPER_MOTOR = 11,
|
||||||
ERROR_FPGA_COMM = 12,
|
ERROR_FPGA_COMM = 12,
|
||||||
ERROR_POWER_SUPPLY = 13,
|
ERROR_POWER_SUPPLY = 13,
|
||||||
ERROR_TEMPERATURE_HIGH = 14,
|
ERROR_TEMPERATURE_HIGH = 14,
|
||||||
|
ERROR_MEMORY_ALLOC = 15,
|
||||||
|
ERROR_WATCHDOG_TIMEOUT = 16,
|
||||||
} SystemError_t;
|
} SystemError_t;
|
||||||
|
|
||||||
/* Extracted critical-error handling logic (post-fix ordering) */
|
/* Extracted critical-error handling logic (matches post-fix main.cpp predicate) */
|
||||||
static void simulate_handleSystemError_critical(SystemError_t error)
|
static void simulate_handleSystemError_critical(SystemError_t error)
|
||||||
{
|
{
|
||||||
/* Only critical errors (PA overcurrent through power supply) trigger e-stop */
|
if ((error >= ERROR_RF_PA_OVERCURRENT && error <= ERROR_POWER_SUPPLY) ||
|
||||||
if (error >= ERROR_RF_PA_OVERCURRENT && error <= ERROR_POWER_SUPPLY) {
|
error == ERROR_TEMPERATURE_HIGH ||
|
||||||
|
error == ERROR_WATCHDOG_TIMEOUT) {
|
||||||
/* FIX 5: set flag BEFORE calling Emergency_Stop */
|
/* FIX 5: set flag BEFORE calling Emergency_Stop */
|
||||||
system_emergency_state = true;
|
system_emergency_state = true;
|
||||||
Mock_Emergency_Stop();
|
Mock_Emergency_Stop();
|
||||||
@@ -93,17 +96,39 @@ int main(void)
|
|||||||
assert(state_was_true_when_estop_called == true);
|
assert(state_was_true_when_estop_called == true);
|
||||||
printf("PASS\n");
|
printf("PASS\n");
|
||||||
|
|
||||||
/* Test 4: Non-critical error → no e-stop, flag stays false */
|
/* Test 4: Overtemp → MUST trigger e-stop (was incorrectly non-critical before fix) */
|
||||||
printf(" Test 4: Non-critical error (no e-stop)... ");
|
printf(" Test 4: Overtemp triggers e-stop... ");
|
||||||
system_emergency_state = false;
|
system_emergency_state = false;
|
||||||
emergency_stop_called = false;
|
emergency_stop_called = false;
|
||||||
|
state_was_true_when_estop_called = false;
|
||||||
simulate_handleSystemError_critical(ERROR_TEMPERATURE_HIGH);
|
simulate_handleSystemError_critical(ERROR_TEMPERATURE_HIGH);
|
||||||
|
assert(emergency_stop_called == true);
|
||||||
|
assert(system_emergency_state == true);
|
||||||
|
assert(state_was_true_when_estop_called == true);
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* Test 5: Watchdog timeout → MUST trigger e-stop */
|
||||||
|
printf(" Test 5: Watchdog timeout triggers e-stop... ");
|
||||||
|
system_emergency_state = false;
|
||||||
|
emergency_stop_called = false;
|
||||||
|
state_was_true_when_estop_called = false;
|
||||||
|
simulate_handleSystemError_critical(ERROR_WATCHDOG_TIMEOUT);
|
||||||
|
assert(emergency_stop_called == true);
|
||||||
|
assert(system_emergency_state == true);
|
||||||
|
assert(state_was_true_when_estop_called == true);
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* Test 6: Non-critical error (memory alloc) → no e-stop */
|
||||||
|
printf(" Test 6: Non-critical error (no e-stop)... ");
|
||||||
|
system_emergency_state = false;
|
||||||
|
emergency_stop_called = false;
|
||||||
|
simulate_handleSystemError_critical(ERROR_MEMORY_ALLOC);
|
||||||
assert(emergency_stop_called == false);
|
assert(emergency_stop_called == false);
|
||||||
assert(system_emergency_state == false);
|
assert(system_emergency_state == false);
|
||||||
printf("PASS\n");
|
printf("PASS\n");
|
||||||
|
|
||||||
/* Test 5: ERROR_NONE → no e-stop */
|
/* Test 7: ERROR_NONE → no e-stop */
|
||||||
printf(" Test 5: ERROR_NONE (no action)... ");
|
printf(" Test 7: ERROR_NONE (no action)... ");
|
||||||
system_emergency_state = false;
|
system_emergency_state = false;
|
||||||
emergency_stop_called = false;
|
emergency_stop_called = false;
|
||||||
simulate_handleSystemError_critical(ERROR_NONE);
|
simulate_handleSystemError_critical(ERROR_NONE);
|
||||||
@@ -111,6 +136,6 @@ int main(void)
|
|||||||
assert(system_emergency_state == false);
|
assert(system_emergency_state == false);
|
||||||
printf("PASS\n");
|
printf("PASS\n");
|
||||||
|
|
||||||
printf("\n=== Gap-3 Fix 5: ALL TESTS PASSED ===\n\n");
|
printf("\n=== Gap-3 Fix 5: ALL 7 TESTS PASSED ===\n\n");
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,132 @@
|
|||||||
|
/*******************************************************************************
|
||||||
|
* test_gap3_health_watchdog_cold_start.c
|
||||||
|
*
|
||||||
|
* Safety bug: checkSystemHealth()'s internal watchdog (step 9, pre-fix) had two
|
||||||
|
* linked defects that, once ERROR_WATCHDOG_TIMEOUT was escalated to
|
||||||
|
* Emergency_Stop() by the overtemp/watchdog PR, would false-latch the radar:
|
||||||
|
*
|
||||||
|
* (1) Cold-start false trip:
|
||||||
|
* static uint32_t last_health_check = 0;
|
||||||
|
* if (HAL_GetTick() - last_health_check > 60000) { ... }
|
||||||
|
* On the very first call, last_health_check == 0, so once the MCU has
|
||||||
|
* been up >60 s (which is typical after the ADAR1000 / AD9523 / ADF4382
|
||||||
|
* init sequence) the subtraction `now - 0` exceeds 60 000 ms and the
|
||||||
|
* watchdog trips spuriously.
|
||||||
|
*
|
||||||
|
* (2) Stale-timestamp after early returns:
|
||||||
|
* last_health_check = HAL_GetTick(); // at END of function
|
||||||
|
* Every earlier sub-check (IMU, BMP180, GPS, PA Idq, temperature) has an
|
||||||
|
* `if (fault) return current_error;` path that skips the update. After a
|
||||||
|
* cumulative 60 s of transient faults, the next clean call compares
|
||||||
|
* `now` against the long-stale `last_health_check` and trips.
|
||||||
|
*
|
||||||
|
* After fix: Watchdog logic moved to function ENTRY. A dedicated cold-start
|
||||||
|
* branch seeds the timestamp on the first call without checking.
|
||||||
|
* On every subsequent call, the elapsed delta is captured FIRST
|
||||||
|
* and last_health_check is updated BEFORE any sub-check runs, so
|
||||||
|
* early returns no longer leave a stale value.
|
||||||
|
*
|
||||||
|
* Test strategy:
|
||||||
|
* Extract the post-fix watchdog predicate into a standalone function that
|
||||||
|
* takes a simulated HAL_GetTick() value and returns whether the watchdog
|
||||||
|
* should trip. Walk through boot + fault sequences that would have tripped
|
||||||
|
* the pre-fix code and assert the post-fix code does NOT trip.
|
||||||
|
******************************************************************************/
|
||||||
|
#include <assert.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
/* --- Post-fix watchdog state + predicate, extracted verbatim --- */
|
||||||
|
static uint32_t last_health_check = 0;
|
||||||
|
|
||||||
|
/* Returns 1 iff this call should raise ERROR_WATCHDOG_TIMEOUT.
|
||||||
|
Updates last_health_check BEFORE returning (matches post-fix behaviour). */
|
||||||
|
static int health_watchdog_step(uint32_t now_tick)
|
||||||
|
{
|
||||||
|
if (last_health_check == 0) {
|
||||||
|
last_health_check = now_tick; /* cold start: seed only, never trip */
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
uint32_t elapsed = now_tick - last_health_check;
|
||||||
|
last_health_check = now_tick; /* update BEFORE any early return */
|
||||||
|
return (elapsed > 60000) ? 1 : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Test helper: reset the static state between scenarios. */
|
||||||
|
static void reset_state(void) { last_health_check = 0; }
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
printf("=== Safety fix: checkSystemHealth() watchdog cold-start + stale-ts ===\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 1: cold-start after 60 s of init must NOT trip ---- */
|
||||||
|
printf(" Test 1: first call at t=75000 ms (post-init) does not trip... ");
|
||||||
|
reset_state();
|
||||||
|
assert(health_watchdog_step(75000) == 0);
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 2: first call far beyond 60 s (PRE-FIX BUG) ------- */
|
||||||
|
printf(" Test 2: first call at t=600000 ms still does not trip... ");
|
||||||
|
reset_state();
|
||||||
|
assert(health_watchdog_step(600000) == 0);
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 3: healthy main-loop pacing (10 ms period) -------- */
|
||||||
|
printf(" Test 3: 1000 calls at 10 ms intervals never trip... ");
|
||||||
|
reset_state();
|
||||||
|
(void)health_watchdog_step(1000); /* seed */
|
||||||
|
for (int i = 1; i <= 1000; i++) {
|
||||||
|
assert(health_watchdog_step(1000 + i * 10) == 0);
|
||||||
|
}
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 4: stale-timestamp after a burst of early returns -
|
||||||
|
Pre-fix bug: many early returns skipped the timestamp update, so a
|
||||||
|
later clean call would compare `now` against a 60+ s old value. Post-fix,
|
||||||
|
every call (including ones that would have early-returned in the real
|
||||||
|
function) updates the timestamp at the top, so this scenario is modelled
|
||||||
|
by calling health_watchdog_step() on every iteration of the main loop. */
|
||||||
|
printf(" Test 4: 70 s of 100 ms-spaced calls after seed do not trip... ");
|
||||||
|
reset_state();
|
||||||
|
(void)health_watchdog_step(50000); /* seed mid-run */
|
||||||
|
for (int i = 1; i <= 700; i++) { /* 70 s @ 100 ms */
|
||||||
|
int tripped = health_watchdog_step(50000 + i * 100);
|
||||||
|
assert(tripped == 0);
|
||||||
|
}
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 5: genuine stall MUST trip ------------------------ */
|
||||||
|
printf(" Test 5: real 60+ s gap between calls does trip... ");
|
||||||
|
reset_state();
|
||||||
|
(void)health_watchdog_step(10000); /* seed */
|
||||||
|
assert(health_watchdog_step(10000 + 60001) == 1);
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 6: exactly 60 s gap is the boundary -- do NOT trip
|
||||||
|
Post-fix predicate uses strict >60000, matching the pre-fix comparator. */
|
||||||
|
printf(" Test 6: exactly 60000 ms gap does not trip (boundary)... ");
|
||||||
|
reset_state();
|
||||||
|
(void)health_watchdog_step(10000);
|
||||||
|
assert(health_watchdog_step(10000 + 60000) == 0);
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 7: trip, then recover on next paced call ---------- */
|
||||||
|
printf(" Test 7: after a genuine stall+trip, next paced call does not re-trip... ");
|
||||||
|
reset_state();
|
||||||
|
(void)health_watchdog_step(5000); /* seed */
|
||||||
|
assert(health_watchdog_step(5000 + 70000) == 1); /* stall -> trip */
|
||||||
|
assert(health_watchdog_step(5000 + 70000 + 10) == 0); /* resume paced */
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* ---------- Scenario 8: HAL_GetTick() 32-bit wrap (~49.7 days) ---------
|
||||||
|
Because we subtract unsigned 32-bit values, wrap is handled correctly as
|
||||||
|
long as the true elapsed time is < 2^32 ms. */
|
||||||
|
printf(" Test 8: tick wrap from 0xFFFFFF00 -> 0x00000064 (200 ms span) does not trip... ");
|
||||||
|
reset_state();
|
||||||
|
(void)health_watchdog_step(0xFFFFFF00u);
|
||||||
|
assert(health_watchdog_step(0x00000064u) == 0); /* elapsed = 0x164 = 356 ms */
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf("\n=== Safety fix: ALL TESTS PASSED ===\n\n");
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
@@ -0,0 +1,119 @@
|
|||||||
|
/*******************************************************************************
|
||||||
|
* test_gap3_overtemp_emergency_stop.c
|
||||||
|
*
|
||||||
|
* Safety bug: handleSystemError() did not escalate ERROR_TEMPERATURE_HIGH
|
||||||
|
* (or ERROR_WATCHDOG_TIMEOUT) to Emergency_Stop().
|
||||||
|
*
|
||||||
|
* Before fix: The critical-error gate was
|
||||||
|
* if (error >= ERROR_RF_PA_OVERCURRENT &&
|
||||||
|
* error <= ERROR_POWER_SUPPLY) { Emergency_Stop(); }
|
||||||
|
* So overtemp (code 14) and watchdog timeout (code 16) fell
|
||||||
|
* through to attemptErrorRecovery()'s default branch (log and
|
||||||
|
* continue), leaving the 10 W GaN PAs biased at >75 °C.
|
||||||
|
*
|
||||||
|
* After fix: The gate also matches ERROR_TEMPERATURE_HIGH and
|
||||||
|
* ERROR_WATCHDOG_TIMEOUT, so thermal and watchdog faults
|
||||||
|
* latch Emergency_Stop() exactly like PA overcurrent.
|
||||||
|
*
|
||||||
|
* Test strategy:
|
||||||
|
* Replicate the critical-error predicate and assert that every error
|
||||||
|
* enum value which threatens RF/power safety is accepted, and that the
|
||||||
|
* non-critical ones (comm, sensor, memory) are not.
|
||||||
|
******************************************************************************/
|
||||||
|
#include <assert.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
/* Mirror of SystemError_t from main.cpp (keep in lockstep). */
|
||||||
|
typedef enum {
|
||||||
|
ERROR_NONE = 0,
|
||||||
|
ERROR_AD9523_CLOCK,
|
||||||
|
ERROR_ADF4382_TX_UNLOCK,
|
||||||
|
ERROR_ADF4382_RX_UNLOCK,
|
||||||
|
ERROR_ADAR1000_COMM,
|
||||||
|
ERROR_ADAR1000_TEMP,
|
||||||
|
ERROR_IMU_COMM,
|
||||||
|
ERROR_BMP180_COMM,
|
||||||
|
ERROR_GPS_COMM,
|
||||||
|
ERROR_RF_PA_OVERCURRENT,
|
||||||
|
ERROR_RF_PA_BIAS,
|
||||||
|
ERROR_STEPPER_MOTOR,
|
||||||
|
ERROR_FPGA_COMM,
|
||||||
|
ERROR_POWER_SUPPLY,
|
||||||
|
ERROR_TEMPERATURE_HIGH,
|
||||||
|
ERROR_MEMORY_ALLOC,
|
||||||
|
ERROR_WATCHDOG_TIMEOUT
|
||||||
|
} SystemError_t;
|
||||||
|
|
||||||
|
/* Extracted post-fix predicate: returns 1 when Emergency_Stop() must fire. */
|
||||||
|
static int triggers_emergency_stop(SystemError_t e)
|
||||||
|
{
|
||||||
|
return ((e >= ERROR_RF_PA_OVERCURRENT && e <= ERROR_POWER_SUPPLY) ||
|
||||||
|
e == ERROR_TEMPERATURE_HIGH ||
|
||||||
|
e == ERROR_WATCHDOG_TIMEOUT);
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
printf("=== Safety fix: overtemp / watchdog -> Emergency_Stop() ===\n");
|
||||||
|
|
||||||
|
/* --- Errors that MUST latch Emergency_Stop --- */
|
||||||
|
printf(" Test 1: ERROR_RF_PA_OVERCURRENT triggers... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_RF_PA_OVERCURRENT));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 2: ERROR_RF_PA_BIAS triggers... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_RF_PA_BIAS));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 3: ERROR_STEPPER_MOTOR triggers... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_STEPPER_MOTOR));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 4: ERROR_FPGA_COMM triggers... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_FPGA_COMM));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 5: ERROR_POWER_SUPPLY triggers... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_POWER_SUPPLY));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 6: ERROR_TEMPERATURE_HIGH triggers (regression)... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_TEMPERATURE_HIGH));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 7: ERROR_WATCHDOG_TIMEOUT triggers (regression)... ");
|
||||||
|
assert(triggers_emergency_stop(ERROR_WATCHDOG_TIMEOUT));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
/* --- Errors that MUST NOT escalate (recoverable / informational) --- */
|
||||||
|
printf(" Test 8: ERROR_NONE does not trigger... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_NONE));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 9: ERROR_AD9523_CLOCK does not trigger... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_AD9523_CLOCK));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 10: ERROR_ADF4382_TX_UNLOCK does not trigger (recoverable)... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_ADF4382_TX_UNLOCK));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 11: ERROR_ADAR1000_COMM does not trigger... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_ADAR1000_COMM));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 12: ERROR_IMU_COMM does not trigger... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_IMU_COMM));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 13: ERROR_GPS_COMM does not trigger... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_GPS_COMM));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf(" Test 14: ERROR_MEMORY_ALLOC does not trigger... ");
|
||||||
|
assert(!triggers_emergency_stop(ERROR_MEMORY_ALLOC));
|
||||||
|
printf("PASS\n");
|
||||||
|
|
||||||
|
printf("\n=== Safety fix: ALL TESTS PASSED ===\n\n");
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
@@ -0,0 +1,853 @@
|
|||||||
|
/*******************************************************************************
|
||||||
|
* test_um982_gps.c -- Unit tests for UM982 GPS driver
|
||||||
|
*
|
||||||
|
* Tests NMEA parsing, checksum validation, coordinate parsing, init sequence,
|
||||||
|
* and validity tracking. Uses the mock HAL infrastructure for UART.
|
||||||
|
*
|
||||||
|
* Build: see Makefile target test_um982_gps
|
||||||
|
* Run: ./test_um982_gps
|
||||||
|
******************************************************************************/
|
||||||
|
#include "stm32_hal_mock.h"
|
||||||
|
#include "../9_1_3_C_Cpp_Code/um982_gps.h"
|
||||||
|
#include "../9_1_3_C_Cpp_Code/um982_gps.c" /* Include .c directly for white-box testing */
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <assert.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
/* ========================= Test helpers ============================== */
|
||||||
|
|
||||||
|
static int tests_passed = 0;
|
||||||
|
static int tests_failed = 0;
|
||||||
|
|
||||||
|
#define TEST(name) \
|
||||||
|
do { printf(" [TEST] %-55s ", name); } while(0)
|
||||||
|
|
||||||
|
#define PASS() \
|
||||||
|
do { printf("PASS\n"); tests_passed++; } while(0)
|
||||||
|
|
||||||
|
#define FAIL(msg) \
|
||||||
|
do { printf("FAIL: %s\n", msg); tests_failed++; } while(0)
|
||||||
|
|
||||||
|
#define ASSERT_TRUE(expr, msg) \
|
||||||
|
do { if (!(expr)) { FAIL(msg); return; } } while(0)
|
||||||
|
|
||||||
|
#define ASSERT_FALSE(expr, msg) \
|
||||||
|
do { if (expr) { FAIL(msg); return; } } while(0)
|
||||||
|
|
||||||
|
#define ASSERT_EQ_INT(a, b, msg) \
|
||||||
|
do { if ((a) != (b)) { \
|
||||||
|
char _buf[256]; \
|
||||||
|
snprintf(_buf, sizeof(_buf), "%s (got %d, expected %d)", msg, (int)(a), (int)(b)); \
|
||||||
|
FAIL(_buf); return; \
|
||||||
|
} } while(0)
|
||||||
|
|
||||||
|
#define ASSERT_NEAR(a, b, tol, msg) \
|
||||||
|
do { if (fabs((double)(a) - (double)(b)) > (tol)) { \
|
||||||
|
char _buf[256]; \
|
||||||
|
snprintf(_buf, sizeof(_buf), "%s (got %.8f, expected %.8f)", msg, (double)(a), (double)(b)); \
|
||||||
|
FAIL(_buf); return; \
|
||||||
|
} } while(0)
|
||||||
|
|
||||||
|
#define ASSERT_NAN(val, msg) \
|
||||||
|
do { if (!isnan(val)) { FAIL(msg); return; } } while(0)
|
||||||
|
|
||||||
|
static UM982_GPS_t gps;
|
||||||
|
|
||||||
|
static void reset_gps(void)
|
||||||
|
{
|
||||||
|
spy_reset();
|
||||||
|
memset(&gps, 0, sizeof(gps));
|
||||||
|
gps.huart = &huart5;
|
||||||
|
gps.heading = NAN;
|
||||||
|
gps.heading_mode = 'V';
|
||||||
|
gps.rmc_status = 'V';
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Checksum tests ============================ */
|
||||||
|
|
||||||
|
static void test_checksum_valid(void)
|
||||||
|
{
|
||||||
|
TEST("checksum: valid GGA");
|
||||||
|
ASSERT_TRUE(um982_verify_checksum(
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47"),
|
||||||
|
"should be valid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_checksum_valid_ths(void)
|
||||||
|
{
|
||||||
|
TEST("checksum: valid THS");
|
||||||
|
ASSERT_TRUE(um982_verify_checksum("$GNTHS,341.3344,A*1F"),
|
||||||
|
"should be valid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_checksum_invalid(void)
|
||||||
|
{
|
||||||
|
TEST("checksum: invalid (wrong value)");
|
||||||
|
ASSERT_FALSE(um982_verify_checksum("$GNTHS,341.3344,A*FF"),
|
||||||
|
"should be invalid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_checksum_missing_star(void)
|
||||||
|
{
|
||||||
|
TEST("checksum: missing * marker");
|
||||||
|
ASSERT_FALSE(um982_verify_checksum("$GNTHS,341.3344,A"),
|
||||||
|
"should be invalid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_checksum_null(void)
|
||||||
|
{
|
||||||
|
TEST("checksum: NULL input");
|
||||||
|
ASSERT_FALSE(um982_verify_checksum(NULL), "should be false");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_checksum_no_dollar(void)
|
||||||
|
{
|
||||||
|
TEST("checksum: missing $ prefix");
|
||||||
|
ASSERT_FALSE(um982_verify_checksum("GNTHS,341.3344,A*1F"),
|
||||||
|
"should be invalid without $");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Coordinate parsing tests ================== */
|
||||||
|
|
||||||
|
static void test_coord_latitude_north(void)
|
||||||
|
{
|
||||||
|
TEST("coord: latitude 4404.14036 N");
|
||||||
|
double lat = um982_parse_coord("4404.14036", 'N');
|
||||||
|
/* 44 + 04.14036/60 = 44.069006 */
|
||||||
|
ASSERT_NEAR(lat, 44.069006, 0.000001, "latitude");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_coord_latitude_south(void)
|
||||||
|
{
|
||||||
|
TEST("coord: latitude 3358.92500 S (negative)");
|
||||||
|
double lat = um982_parse_coord("3358.92500", 'S');
|
||||||
|
ASSERT_TRUE(lat < 0.0, "should be negative for S");
|
||||||
|
ASSERT_NEAR(lat, -(33.0 + 58.925/60.0), 0.000001, "latitude");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_coord_longitude_3digit(void)
|
||||||
|
{
|
||||||
|
TEST("coord: longitude 12118.85961 W (3-digit degrees)");
|
||||||
|
double lon = um982_parse_coord("12118.85961", 'W');
|
||||||
|
/* 121 + 18.85961/60 = 121.314327 */
|
||||||
|
ASSERT_TRUE(lon < 0.0, "should be negative for W");
|
||||||
|
ASSERT_NEAR(lon, -(121.0 + 18.85961/60.0), 0.000001, "longitude");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_coord_longitude_east(void)
|
||||||
|
{
|
||||||
|
TEST("coord: longitude 11614.19729 E");
|
||||||
|
double lon = um982_parse_coord("11614.19729", 'E');
|
||||||
|
ASSERT_TRUE(lon > 0.0, "should be positive for E");
|
||||||
|
ASSERT_NEAR(lon, 116.0 + 14.19729/60.0, 0.000001, "longitude");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_coord_empty(void)
|
||||||
|
{
|
||||||
|
TEST("coord: empty string returns NAN");
|
||||||
|
ASSERT_NAN(um982_parse_coord("", 'N'), "should be NAN");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_coord_null(void)
|
||||||
|
{
|
||||||
|
TEST("coord: NULL returns NAN");
|
||||||
|
ASSERT_NAN(um982_parse_coord(NULL, 'N'), "should be NAN");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_coord_no_dot(void)
|
||||||
|
{
|
||||||
|
TEST("coord: no decimal point returns NAN");
|
||||||
|
ASSERT_NAN(um982_parse_coord("440414036", 'N'), "should be NAN");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= GGA parsing tests ========================= */
|
||||||
|
|
||||||
|
static void test_parse_gga_full(void)
|
||||||
|
{
|
||||||
|
TEST("GGA: full sentence with all fields");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(1000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.latitude, 44.069006, 0.0001, "latitude");
|
||||||
|
ASSERT_NEAR(gps.longitude, -(121.0 + 18.85961/60.0), 0.0001, "longitude");
|
||||||
|
ASSERT_EQ_INT(gps.fix_quality, 1, "fix quality");
|
||||||
|
ASSERT_EQ_INT(gps.num_satellites, 12, "num sats");
|
||||||
|
ASSERT_NEAR(gps.hdop, 0.98, 0.01, "hdop");
|
||||||
|
ASSERT_NEAR(gps.altitude, 1113.0, 0.1, "altitude");
|
||||||
|
ASSERT_NEAR(gps.geoid_sep, -21.3, 0.1, "geoid sep");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_parse_gga_rtk_fixed(void)
|
||||||
|
{
|
||||||
|
TEST("GGA: RTK fixed (quality=4)");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,023634.00,4004.73871635,N,11614.19729418,E,4,28,0.7,61.0988,M,-8.4923,M,,*5D");
|
||||||
|
|
||||||
|
ASSERT_EQ_INT(gps.fix_quality, 4, "RTK fixed");
|
||||||
|
ASSERT_EQ_INT(gps.num_satellites, 28, "num sats");
|
||||||
|
ASSERT_NEAR(gps.latitude, 40.0 + 4.73871635/60.0, 0.0000001, "latitude");
|
||||||
|
ASSERT_NEAR(gps.longitude, 116.0 + 14.19729418/60.0, 0.0000001, "longitude");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_parse_gga_no_fix(void)
|
||||||
|
{
|
||||||
|
TEST("GGA: no fix (quality=0)");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
/* Compute checksum for this sentence */
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||||
|
|
||||||
|
ASSERT_EQ_INT(gps.fix_quality, 0, "no fix");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= RMC parsing tests ========================= */
|
||||||
|
|
||||||
|
static void test_parse_rmc_valid(void)
|
||||||
|
{
|
||||||
|
TEST("RMC: valid position and speed");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(2000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNRMC,001031.00,A,4404.13993,N,12118.86023,W,0.146,,100117,,,A*7B");
|
||||||
|
|
||||||
|
ASSERT_EQ_INT(gps.rmc_status, 'A', "status");
|
||||||
|
ASSERT_NEAR(gps.latitude, 44.0 + 4.13993/60.0, 0.0001, "latitude");
|
||||||
|
ASSERT_NEAR(gps.longitude, -(121.0 + 18.86023/60.0), 0.0001, "longitude");
|
||||||
|
ASSERT_NEAR(gps.speed_knots, 0.146, 0.001, "speed");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_parse_rmc_void(void)
|
||||||
|
{
|
||||||
|
TEST("RMC: void status (no valid fix)");
|
||||||
|
reset_gps();
|
||||||
|
gps.latitude = 12.34; /* Pre-set to check it doesn't get overwritten */
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNRMC,235959.00,V,,,,,,,100117,,,N*64");
|
||||||
|
|
||||||
|
ASSERT_EQ_INT(gps.rmc_status, 'V', "void status");
|
||||||
|
ASSERT_NEAR(gps.latitude, 12.34, 0.001, "lat should not change on void");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= THS parsing tests ========================= */
|
||||||
|
|
||||||
|
static void test_parse_ths_autonomous(void)
|
||||||
|
{
|
||||||
|
TEST("THS: autonomous heading 341.3344");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(3000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 341.3344, 0.001, "heading");
|
||||||
|
ASSERT_EQ_INT(gps.heading_mode, 'A', "mode");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_parse_ths_not_valid(void)
|
||||||
|
{
|
||||||
|
TEST("THS: not valid mode");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,,V*10");
|
||||||
|
|
||||||
|
ASSERT_NAN(gps.heading, "heading should be NAN when empty");
|
||||||
|
ASSERT_EQ_INT(gps.heading_mode, 'V', "mode V");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_parse_ths_zero(void)
|
||||||
|
{
|
||||||
|
TEST("THS: heading exactly 0.0000");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,0.0000,A*19");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 0.0, 0.001, "heading zero");
|
||||||
|
ASSERT_EQ_INT(gps.heading_mode, 'A', "mode A");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_parse_ths_360_boundary(void)
|
||||||
|
{
|
||||||
|
TEST("THS: heading near 360");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,359.9999,D*13");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 359.9999, 0.001, "heading near 360");
|
||||||
|
ASSERT_EQ_INT(gps.heading_mode, 'D', "mode D");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= VTG parsing tests ========================= */
|
||||||
|
|
||||||
|
static void test_parse_vtg(void)
|
||||||
|
{
|
||||||
|
TEST("VTG: course and speed");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GPVTG,220.86,T,,M,2.550,N,4.724,K,A*34");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.course_true, 220.86, 0.01, "course");
|
||||||
|
ASSERT_NEAR(gps.speed_knots, 2.550, 0.001, "speed knots");
|
||||||
|
ASSERT_NEAR(gps.speed_kmh, 4.724, 0.001, "speed kmh");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Talker ID tests =========================== */
|
||||||
|
|
||||||
|
static void test_talker_gp(void)
|
||||||
|
{
|
||||||
|
TEST("talker: GP prefix parses correctly");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GPTHS,123.4567,A*07");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 123.4567, 0.001, "heading with GP");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_talker_gl(void)
|
||||||
|
{
|
||||||
|
TEST("talker: GL prefix parses correctly");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GLTHS,123.4567,A*1B");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 123.4567, 0.001, "heading with GL");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Feed / line assembly tests ================ */
|
||||||
|
|
||||||
|
static void test_feed_single_sentence(void)
|
||||||
|
{
|
||||||
|
TEST("feed: single complete sentence with CRLF");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(5000);
|
||||||
|
|
||||||
|
const char *data = "$GNTHS,341.3344,A*1F\r\n";
|
||||||
|
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 341.3344, 0.001, "heading");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_feed_multiple_sentences(void)
|
||||||
|
{
|
||||||
|
TEST("feed: multiple sentences in one chunk");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(5000);
|
||||||
|
|
||||||
|
const char *data =
|
||||||
|
"$GNTHS,100.0000,A*18\r\n"
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47\r\n";
|
||||||
|
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 100.0, 0.01, "heading from THS");
|
||||||
|
ASSERT_EQ_INT(gps.fix_quality, 1, "fix from GGA");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_feed_partial_then_complete(void)
|
||||||
|
{
|
||||||
|
TEST("feed: partial bytes then complete");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(5000);
|
||||||
|
|
||||||
|
const char *part1 = "$GNTHS,200.";
|
||||||
|
const char *part2 = "5000,A*1E\r\n";
|
||||||
|
um982_feed(&gps, (const uint8_t *)part1, (uint16_t)strlen(part1));
|
||||||
|
/* Heading should not be set yet */
|
||||||
|
ASSERT_NAN(gps.heading, "should be NAN before complete");
|
||||||
|
|
||||||
|
um982_feed(&gps, (const uint8_t *)part2, (uint16_t)strlen(part2));
|
||||||
|
ASSERT_NEAR(gps.heading, 200.5, 0.01, "heading after complete");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_feed_bad_checksum_rejected(void)
|
||||||
|
{
|
||||||
|
TEST("feed: bad checksum sentence is rejected");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(5000);
|
||||||
|
|
||||||
|
const char *data = "$GNTHS,999.0000,A*FF\r\n";
|
||||||
|
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||||
|
|
||||||
|
ASSERT_NAN(gps.heading, "heading should remain NAN");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_feed_versiona_response(void)
|
||||||
|
{
|
||||||
|
TEST("feed: VERSIONA response sets flag");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
const char *data = "#VERSIONA,79,GPS,FINE,2326,378237000,15434,0,18,889;\"UM982\"\r\n";
|
||||||
|
um982_feed(&gps, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||||
|
|
||||||
|
ASSERT_TRUE(gps.version_received, "version_received should be true");
|
||||||
|
ASSERT_TRUE(gps.initialized, "VERSIONA should mark communication alive");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Validity / age tests ====================== */
|
||||||
|
|
||||||
|
static void test_heading_valid_within_timeout(void)
|
||||||
|
{
|
||||||
|
TEST("validity: heading valid within timeout");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(10000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||||
|
|
||||||
|
/* Still at tick 10000 */
|
||||||
|
ASSERT_TRUE(um982_is_heading_valid(&gps), "should be valid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_heading_invalid_after_timeout(void)
|
||||||
|
{
|
||||||
|
TEST("validity: heading invalid after 2s timeout");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(10000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||||
|
|
||||||
|
/* Advance past timeout */
|
||||||
|
mock_set_tick(12500);
|
||||||
|
ASSERT_FALSE(um982_is_heading_valid(&gps), "should be invalid after 2.5s");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_heading_invalid_mode_v(void)
|
||||||
|
{
|
||||||
|
TEST("validity: heading invalid with mode V");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(10000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,,V*10");
|
||||||
|
|
||||||
|
ASSERT_FALSE(um982_is_heading_valid(&gps), "mode V is invalid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_position_valid(void)
|
||||||
|
{
|
||||||
|
TEST("validity: position valid with fix quality 1");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(10000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||||
|
|
||||||
|
ASSERT_TRUE(um982_is_position_valid(&gps), "should be valid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_position_invalid_no_fix(void)
|
||||||
|
{
|
||||||
|
TEST("validity: position invalid with no fix");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(10000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||||
|
|
||||||
|
ASSERT_FALSE(um982_is_position_valid(&gps), "no fix = invalid");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_position_age_uses_last_valid_fix(void)
|
||||||
|
{
|
||||||
|
TEST("age: position age uses last valid fix, not no-fix GGA");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
mock_set_tick(10000);
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||||
|
|
||||||
|
mock_set_tick(12000);
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||||
|
|
||||||
|
mock_set_tick(12500);
|
||||||
|
ASSERT_EQ_INT(um982_position_age(&gps), 2500, "age should still be from last valid fix");
|
||||||
|
ASSERT_FALSE(um982_is_position_valid(&gps), "latest no-fix GGA should invalidate position");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_heading_age(void)
|
||||||
|
{
|
||||||
|
TEST("age: heading age computed correctly");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(10000);
|
||||||
|
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||||
|
|
||||||
|
mock_set_tick(10500);
|
||||||
|
uint32_t age = um982_heading_age(&gps);
|
||||||
|
ASSERT_EQ_INT(age, 500, "age should be 500ms");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Send command tests ======================== */
|
||||||
|
|
||||||
|
static void test_send_command_appends_crlf(void)
|
||||||
|
{
|
||||||
|
TEST("send_command: appends \\r\\n");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
um982_send_command(&gps, "GPGGA COM2 1");
|
||||||
|
|
||||||
|
/* Check that TX buffer contains "GPGGA COM2 1\r\n" */
|
||||||
|
const char *expected = "GPGGA COM2 1\r\n";
|
||||||
|
ASSERT_TRUE(mock_uart_tx_len == strlen(expected), "TX length");
|
||||||
|
ASSERT_TRUE(memcmp(mock_uart_tx_buf, expected, strlen(expected)) == 0,
|
||||||
|
"TX content should be 'GPGGA COM2 1\\r\\n'");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_send_command_null_safety(void)
|
||||||
|
{
|
||||||
|
TEST("send_command: NULL gps returns false");
|
||||||
|
ASSERT_FALSE(um982_send_command(NULL, "RESET"), "should return false");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Init sequence tests ======================= */
|
||||||
|
|
||||||
|
static void test_init_sends_correct_commands(void)
|
||||||
|
{
|
||||||
|
TEST("init: sends correct command sequence");
|
||||||
|
spy_reset();
|
||||||
|
mock_uart_tx_clear();
|
||||||
|
|
||||||
|
/* Pre-load VERSIONA response so init succeeds */
|
||||||
|
const char *ver_resp = "#VERSIONA,79,GPS,FINE,2326,378237000,15434,0,18,889;\"UM982\"\r\n";
|
||||||
|
mock_uart_rx_load(&huart5, (const uint8_t *)ver_resp, (uint16_t)strlen(ver_resp));
|
||||||
|
|
||||||
|
UM982_GPS_t init_gps;
|
||||||
|
bool ok = um982_init(&init_gps, &huart5, 50.0f, 3.0f);
|
||||||
|
|
||||||
|
ASSERT_TRUE(ok, "init should succeed");
|
||||||
|
ASSERT_TRUE(init_gps.initialized, "should be initialized");
|
||||||
|
|
||||||
|
/* Verify TX buffer contains expected commands */
|
||||||
|
const char *tx = (const char *)mock_uart_tx_buf;
|
||||||
|
ASSERT_TRUE(strstr(tx, "UNLOG\r\n") != NULL, "should send UNLOG");
|
||||||
|
ASSERT_TRUE(strstr(tx, "CONFIG HEADING FIXLENGTH\r\n") != NULL, "should send CONFIG HEADING");
|
||||||
|
ASSERT_TRUE(strstr(tx, "CONFIG HEADING LENGTH 50 3\r\n") != NULL, "should send LENGTH");
|
||||||
|
ASSERT_TRUE(strstr(tx, "GPGGA COM2 1\r\n") != NULL, "should enable GGA");
|
||||||
|
ASSERT_TRUE(strstr(tx, "GPRMC COM2 1\r\n") != NULL, "should enable RMC");
|
||||||
|
ASSERT_TRUE(strstr(tx, "GPTHS COM2 0.2\r\n") != NULL, "should enable THS at 5Hz");
|
||||||
|
ASSERT_TRUE(strstr(tx, "SAVECONFIG\r\n") == NULL, "should NOT save config (NVM wear)");
|
||||||
|
ASSERT_TRUE(strstr(tx, "VERSIONA\r\n") != NULL, "should query version");
|
||||||
|
|
||||||
|
/* Verify command order: UNLOG should come before GPGGA */
|
||||||
|
const char *unlog_pos = strstr(tx, "UNLOG\r\n");
|
||||||
|
const char *gpgga_pos = strstr(tx, "GPGGA COM2 1\r\n");
|
||||||
|
ASSERT_TRUE(unlog_pos < gpgga_pos, "UNLOG should precede GPGGA");
|
||||||
|
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_init_no_baseline(void)
|
||||||
|
{
|
||||||
|
TEST("init: baseline=0 skips LENGTH command");
|
||||||
|
spy_reset();
|
||||||
|
mock_uart_tx_clear();
|
||||||
|
|
||||||
|
const char *ver_resp = "#VERSIONA,79,GPS,FINE,2326,378237000,15434,0,18,889;\"UM982\"\r\n";
|
||||||
|
mock_uart_rx_load(&huart5, (const uint8_t *)ver_resp, (uint16_t)strlen(ver_resp));
|
||||||
|
|
||||||
|
UM982_GPS_t init_gps;
|
||||||
|
um982_init(&init_gps, &huart5, 0.0f, 0.0f);
|
||||||
|
|
||||||
|
const char *tx = (const char *)mock_uart_tx_buf;
|
||||||
|
ASSERT_TRUE(strstr(tx, "CONFIG HEADING LENGTH") == NULL, "should NOT send LENGTH");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_init_fails_no_version(void)
|
||||||
|
{
|
||||||
|
TEST("init: fails if no VERSIONA response");
|
||||||
|
spy_reset();
|
||||||
|
mock_uart_tx_clear();
|
||||||
|
|
||||||
|
/* Don't load any RX data — init should timeout */
|
||||||
|
UM982_GPS_t init_gps;
|
||||||
|
bool ok = um982_init(&init_gps, &huart5, 50.0f, 3.0f);
|
||||||
|
|
||||||
|
ASSERT_FALSE(ok, "init should fail without version response");
|
||||||
|
ASSERT_FALSE(init_gps.initialized, "should not be initialized");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_nmea_traffic_sets_initialized_without_versiona(void)
|
||||||
|
{
|
||||||
|
TEST("init state: supported NMEA traffic sets initialized");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
ASSERT_FALSE(gps.initialized, "should start uninitialized");
|
||||||
|
um982_parse_sentence(&gps, "$GNTHS,341.3344,A*1F");
|
||||||
|
ASSERT_TRUE(gps.initialized, "supported NMEA should mark communication alive");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Edge case tests =========================== */
|
||||||
|
|
||||||
|
static void test_empty_fields_handled(void)
|
||||||
|
{
|
||||||
|
TEST("edge: GGA with empty lat/lon fields");
|
||||||
|
reset_gps();
|
||||||
|
gps.latitude = 99.99;
|
||||||
|
gps.longitude = 99.99;
|
||||||
|
|
||||||
|
/* GGA with empty position fields (no fix) */
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,235959.00,,,,,0,00,99.99,,,,,,*79");
|
||||||
|
|
||||||
|
ASSERT_EQ_INT(gps.fix_quality, 0, "no fix");
|
||||||
|
/* Latitude/longitude should not be updated (fields are empty) */
|
||||||
|
ASSERT_NEAR(gps.latitude, 99.99, 0.01, "lat unchanged");
|
||||||
|
ASSERT_NEAR(gps.longitude, 99.99, 0.01, "lon unchanged");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_sentence_too_short(void)
|
||||||
|
{
|
||||||
|
TEST("edge: sentence too short to have formatter");
|
||||||
|
reset_gps();
|
||||||
|
/* Should not crash */
|
||||||
|
um982_parse_sentence(&gps, "$GN");
|
||||||
|
um982_parse_sentence(&gps, "$");
|
||||||
|
um982_parse_sentence(&gps, "");
|
||||||
|
um982_parse_sentence(&gps, NULL);
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_line_overflow(void)
|
||||||
|
{
|
||||||
|
TEST("edge: oversized line is dropped");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
/* Create a line longer than UM982_LINE_BUF_SIZE */
|
||||||
|
char big[200];
|
||||||
|
memset(big, 'X', sizeof(big));
|
||||||
|
big[0] = '$';
|
||||||
|
big[198] = '\n';
|
||||||
|
big[199] = '\0';
|
||||||
|
|
||||||
|
um982_feed(&gps, (const uint8_t *)big, 199);
|
||||||
|
/* Should not crash, heading should still be NAN */
|
||||||
|
ASSERT_NAN(gps.heading, "no valid data from overflow");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_process_via_mock_uart(void)
|
||||||
|
{
|
||||||
|
TEST("process: reads from mock UART RX buffer");
|
||||||
|
reset_gps();
|
||||||
|
mock_set_tick(5000);
|
||||||
|
|
||||||
|
/* Load data into mock UART RX */
|
||||||
|
const char *data = "$GNTHS,275.1234,D*18\r\n";
|
||||||
|
mock_uart_rx_load(&huart5, (const uint8_t *)data, (uint16_t)strlen(data));
|
||||||
|
|
||||||
|
/* Call process() which reads from UART */
|
||||||
|
um982_process(&gps);
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.heading, 275.1234, 0.001, "heading via process()");
|
||||||
|
ASSERT_EQ_INT(gps.heading_mode, 'D', "mode D");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= PR #68 bug regression tests =============== */
|
||||||
|
|
||||||
|
/* These tests specifically verify the bugs found in the reverted PR #68 */
|
||||||
|
|
||||||
|
static void test_regression_sentence_id_with_gn_prefix(void)
|
||||||
|
{
|
||||||
|
TEST("regression: GN-prefixed GGA is correctly identified");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
/* PR #68 bug: strncmp(sentence, "GGA", 3) compared "GNG" vs "GGA" — never matched.
|
||||||
|
* Our fix: skip 2-char talker ID, compare at sentence+3. */
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||||
|
|
||||||
|
ASSERT_EQ_INT(gps.fix_quality, 1, "GGA should parse with GN prefix");
|
||||||
|
ASSERT_NEAR(gps.latitude, 44.069006, 0.001, "latitude should be parsed");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_regression_longitude_3digit_degrees(void)
|
||||||
|
{
|
||||||
|
TEST("regression: 3-digit longitude degrees parsed correctly");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
/* PR #68 bug: hardcoded 2-digit degrees for longitude.
|
||||||
|
* 12118.85961 should be 121° 18.85961' = 121.314327° */
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||||
|
|
||||||
|
ASSERT_NEAR(gps.longitude, -(121.0 + 18.85961/60.0), 0.0001,
|
||||||
|
"longitude 121° should not be parsed as 12°");
|
||||||
|
ASSERT_TRUE(gps.longitude < -100.0, "longitude should be > 100 degrees");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_regression_hemisphere_no_ptr_corrupt(void)
|
||||||
|
{
|
||||||
|
TEST("regression: hemisphere parsing doesn't corrupt field pointer");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
/* PR #68 bug: GGA/RMC hemisphere cases manually advanced ptr,
|
||||||
|
* desynchronizing from field counter. Our parser uses proper tokenizer. */
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNGGA,001043.00,4404.14036,N,12118.85961,W,1,12,0.98,1113.0,M,-21.3,M*47");
|
||||||
|
|
||||||
|
/* After lat/lon, remaining fields should be correct */
|
||||||
|
ASSERT_EQ_INT(gps.num_satellites, 12, "sats after hemisphere");
|
||||||
|
ASSERT_NEAR(gps.hdop, 0.98, 0.01, "hdop after hemisphere");
|
||||||
|
ASSERT_NEAR(gps.altitude, 1113.0, 0.1, "altitude after hemisphere");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void test_regression_rmc_also_parsed(void)
|
||||||
|
{
|
||||||
|
TEST("regression: RMC sentence is actually parsed (not dead code)");
|
||||||
|
reset_gps();
|
||||||
|
|
||||||
|
/* PR #68 bug: identifySentence never matched GGA/RMC, so position
|
||||||
|
* parsing was dead code. */
|
||||||
|
um982_parse_sentence(&gps,
|
||||||
|
"$GNRMC,001031.00,A,4404.13993,N,12118.86023,W,0.146,,100117,,,A*7B");
|
||||||
|
|
||||||
|
ASSERT_TRUE(gps.latitude > 44.0, "RMC lat should be parsed");
|
||||||
|
ASSERT_TRUE(gps.longitude < -121.0, "RMC lon should be parsed");
|
||||||
|
ASSERT_NEAR(gps.speed_knots, 0.146, 0.001, "RMC speed");
|
||||||
|
PASS();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ========================= Main ====================================== */
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
printf("=== UM982 GPS Driver Tests ===\n\n");
|
||||||
|
|
||||||
|
printf("--- Checksum ---\n");
|
||||||
|
test_checksum_valid();
|
||||||
|
test_checksum_valid_ths();
|
||||||
|
test_checksum_invalid();
|
||||||
|
test_checksum_missing_star();
|
||||||
|
test_checksum_null();
|
||||||
|
test_checksum_no_dollar();
|
||||||
|
|
||||||
|
printf("\n--- Coordinate Parsing ---\n");
|
||||||
|
test_coord_latitude_north();
|
||||||
|
test_coord_latitude_south();
|
||||||
|
test_coord_longitude_3digit();
|
||||||
|
test_coord_longitude_east();
|
||||||
|
test_coord_empty();
|
||||||
|
test_coord_null();
|
||||||
|
test_coord_no_dot();
|
||||||
|
|
||||||
|
printf("\n--- GGA Parsing ---\n");
|
||||||
|
test_parse_gga_full();
|
||||||
|
test_parse_gga_rtk_fixed();
|
||||||
|
test_parse_gga_no_fix();
|
||||||
|
|
||||||
|
printf("\n--- RMC Parsing ---\n");
|
||||||
|
test_parse_rmc_valid();
|
||||||
|
test_parse_rmc_void();
|
||||||
|
|
||||||
|
printf("\n--- THS Parsing ---\n");
|
||||||
|
test_parse_ths_autonomous();
|
||||||
|
test_parse_ths_not_valid();
|
||||||
|
test_parse_ths_zero();
|
||||||
|
test_parse_ths_360_boundary();
|
||||||
|
|
||||||
|
printf("\n--- VTG Parsing ---\n");
|
||||||
|
test_parse_vtg();
|
||||||
|
|
||||||
|
printf("\n--- Talker IDs ---\n");
|
||||||
|
test_talker_gp();
|
||||||
|
test_talker_gl();
|
||||||
|
|
||||||
|
printf("\n--- Feed / Line Assembly ---\n");
|
||||||
|
test_feed_single_sentence();
|
||||||
|
test_feed_multiple_sentences();
|
||||||
|
test_feed_partial_then_complete();
|
||||||
|
test_feed_bad_checksum_rejected();
|
||||||
|
test_feed_versiona_response();
|
||||||
|
|
||||||
|
printf("\n--- Validity / Age ---\n");
|
||||||
|
test_heading_valid_within_timeout();
|
||||||
|
test_heading_invalid_after_timeout();
|
||||||
|
test_heading_invalid_mode_v();
|
||||||
|
test_position_valid();
|
||||||
|
test_position_invalid_no_fix();
|
||||||
|
test_position_age_uses_last_valid_fix();
|
||||||
|
test_heading_age();
|
||||||
|
|
||||||
|
printf("\n--- Send Command ---\n");
|
||||||
|
test_send_command_appends_crlf();
|
||||||
|
test_send_command_null_safety();
|
||||||
|
|
||||||
|
printf("\n--- Init Sequence ---\n");
|
||||||
|
test_init_sends_correct_commands();
|
||||||
|
test_init_no_baseline();
|
||||||
|
test_init_fails_no_version();
|
||||||
|
test_nmea_traffic_sets_initialized_without_versiona();
|
||||||
|
|
||||||
|
printf("\n--- Edge Cases ---\n");
|
||||||
|
test_empty_fields_handled();
|
||||||
|
test_sentence_too_short();
|
||||||
|
test_line_overflow();
|
||||||
|
test_process_via_mock_uart();
|
||||||
|
|
||||||
|
printf("\n--- PR #68 Regression ---\n");
|
||||||
|
test_regression_sentence_id_with_gn_prefix();
|
||||||
|
test_regression_longitude_3digit_degrees();
|
||||||
|
test_regression_hemisphere_no_ptr_corrupt();
|
||||||
|
test_regression_rmc_also_parsed();
|
||||||
|
|
||||||
|
printf("\n===============================================\n");
|
||||||
|
printf(" Results: %d passed, %d failed (of %d total)\n",
|
||||||
|
tests_passed, tests_failed, tests_passed + tests_failed);
|
||||||
|
printf("===============================================\n");
|
||||||
|
|
||||||
|
return tests_failed > 0 ? 1 : 0;
|
||||||
|
}
|
||||||
@@ -32,11 +32,50 @@ localparam COMB_WIDTH = 28;
|
|||||||
// adjacent DSP48E1 tiles — zero fabric delay, guaranteed to meet 400+ MHz
|
// adjacent DSP48E1 tiles — zero fabric delay, guaranteed to meet 400+ MHz
|
||||||
// on 7-series regardless of speed grade.
|
// on 7-series regardless of speed grade.
|
||||||
//
|
//
|
||||||
// Active-high reset derived from reset_n (inverted).
|
// Active-high reset derived from reset_n (inverted and REGISTERED).
|
||||||
// CEP (clock enable for P register) gated by data_valid.
|
// CEP (clock enable for P register) gated by data_valid.
|
||||||
// ============================================================================
|
//
|
||||||
|
// ----------------------------------------------------------------------------
|
||||||
wire reset_h = ~reset_n; // active-high reset for DSP48E1 RSTP
|
// RESET FAN-OUT INVARIANT (Build N+1 fix for WNS=-0.626ns at 400 MHz):
|
||||||
|
// ----------------------------------------------------------------------------
|
||||||
|
// Previously this was a combinational wire (`wire reset_h = ~reset_n`). Vivado
|
||||||
|
// collapsed all per-module inversions across the DDC hierarchy into a SINGLE
|
||||||
|
// shared LUT1, whose output fanned out to 702 loads (DSP48E1 RSTP/RSTB/RSTC
|
||||||
|
// plus FDRE R pins of all comb-stage DSP48E1s inferred via use_dsp="yes").
|
||||||
|
// Route delay alone on that net was 2.019–2.268 ns — nearly one full 2.5 ns
|
||||||
|
// period. Timing failed by 626 ps on the 400 MHz domain.
|
||||||
|
//
|
||||||
|
// Fix: convert reset_h to a REGISTERED signal with (* max_fanout = 50 *).
|
||||||
|
// Vivado treats max_fanout on a REG (not a wire) as authoritative and
|
||||||
|
// replicates the register into N copies, each placed near its ≈50 loads.
|
||||||
|
// Invariants preserved:
|
||||||
|
// I1 (correctness): reset_h is still active-high, equals ~reset_n
|
||||||
|
// after one clk edge; CIC reset is a RECEIVER-side
|
||||||
|
// synchronizer anyway (driven by reset_n_400m which
|
||||||
|
// is already sync'd in the parent DDC), so adding
|
||||||
|
// one more clk cycle of latency is safe.
|
||||||
|
// I2 (glitch-free): Registered output => inherently glitch-free,
|
||||||
|
// feeding DSP48E1 RST pins (which are synchronous
|
||||||
|
// to CLK, so they capture on the same edge anyway).
|
||||||
|
// I3 (power-up safety): reset_h is NOT async-reset itself. On power-up,
|
||||||
|
// FDRE INIT=0 starts reset_h LOW. First clk edge
|
||||||
|
// samples ~reset_n which is LOW on power-up (the
|
||||||
|
// parent DDC holds reset_n_400m low until the 2-
|
||||||
|
// stage synchronizer releases), so reset_h goes
|
||||||
|
// HIGH on cycle 1 and all DSPs see reset during
|
||||||
|
// the following cycles. System is held in reset
|
||||||
|
// for enough cycles that any initial register
|
||||||
|
// state garbage is overwritten. ✅
|
||||||
|
// I4 (reset de-assertion):reset_h goes LOW one cycle AFTER reset_n_400m
|
||||||
|
// goes HIGH. Downstream DSPs come out of reset on
|
||||||
|
// the next clk edge after that. Total latency
|
||||||
|
// from system reset release to first valid sample:
|
||||||
|
// 2 (sync chain) + 1 (reset_h reg) + 1 (first
|
||||||
|
// DSP output) = 4 cycles at 400 MHz = 10 ns.
|
||||||
|
// Negligible vs system reset assertion duration.
|
||||||
|
// ----------------------------------------------------------------------------
|
||||||
|
(* max_fanout = 50 *) reg reset_h = 1'b1; // INIT=1'b1: registers start in reset state on power-up
|
||||||
|
always @(posedge clk) reset_h <= ~reset_n;
|
||||||
|
|
||||||
// Sign-extended input for integrator_0 C port (48-bit)
|
// Sign-extended input for integrator_0 C port (48-bit)
|
||||||
wire [ACC_WIDTH-1:0] data_in_c = {{(ACC_WIDTH-18){data_in[17]}}, data_in};
|
wire [ACC_WIDTH-1:0] data_in_c = {{(ACC_WIDTH-18){data_in[17]}}, data_in};
|
||||||
@@ -699,10 +738,11 @@ initial begin
|
|||||||
end
|
end
|
||||||
|
|
||||||
// Decimation control + monitoring (integrators are now DSP48E1 instances)
|
// Decimation control + monitoring (integrators are now DSP48E1 instances)
|
||||||
// Sync reset: enables FDRE inference for better timing at 400 MHz.
|
// Sync reset via reset_h (registered, max_fanout=50) — eliminates the shared
|
||||||
// Reset is already synchronous to clk via reset synchronizer in parent module.
|
// LUT1 inverter that previously fanned out to all fabric FDRE R pins plus
|
||||||
|
// DSP48E1 RST pins (702 loads total). See "RESET FAN-OUT INVARIANT" at top.
|
||||||
always @(posedge clk) begin
|
always @(posedge clk) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
integrator_sampled <= 0;
|
integrator_sampled <= 0;
|
||||||
decimation_counter <= 0;
|
decimation_counter <= 0;
|
||||||
data_valid_delayed <= 0;
|
data_valid_delayed <= 0;
|
||||||
@@ -755,9 +795,9 @@ always @(posedge clk) begin
|
|||||||
end
|
end
|
||||||
|
|
||||||
// Pipeline the valid signal for comb section
|
// Pipeline the valid signal for comb section
|
||||||
// Sync reset: matches decimation control block reset style.
|
// Sync reset via reset_h — same replicated-register source as DSP48E1 RSTs.
|
||||||
always @(posedge clk) begin
|
always @(posedge clk) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
data_valid_comb <= 0;
|
data_valid_comb <= 0;
|
||||||
data_valid_comb_pipe <= 0;
|
data_valid_comb_pipe <= 0;
|
||||||
data_valid_comb_0_out <= 0;
|
data_valid_comb_0_out <= 0;
|
||||||
@@ -792,7 +832,7 @@ end
|
|||||||
// - Each stage: comb[i] = comb[i-1] - comb_delay[i][last]
|
// - Each stage: comb[i] = comb[i-1] - comb_delay[i][last]
|
||||||
|
|
||||||
always @(posedge clk) begin
|
always @(posedge clk) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
for (i = 0; i < STAGES; i = i + 1) begin
|
for (i = 0; i < STAGES; i = i + 1) begin
|
||||||
comb[i] <= 0;
|
comb[i] <= 0;
|
||||||
for (j = 0; j < COMB_DELAY; j = j + 1) begin
|
for (j = 0; j < COMB_DELAY; j = j + 1) begin
|
||||||
|
|||||||
@@ -224,7 +224,7 @@ set_property IOSTANDARD LVCMOS33 [get_ports {stm32_mixers_enable}]
|
|||||||
|
|
||||||
# DIG_5 = H11, DIG_6 = G12, DIG_7 = H12 — FPGA→STM32 status outputs
|
# DIG_5 = H11, DIG_6 = G12, DIG_7 = H12 — FPGA→STM32 status outputs
|
||||||
# DIG_5: AGC saturation flag (PD13 on STM32)
|
# DIG_5: AGC saturation flag (PD13 on STM32)
|
||||||
# DIG_6: reserved (PD14)
|
# DIG_6: AGC enable flag (PD14) — mirrors FPGA host_agc_enable to STM32
|
||||||
# DIG_7: reserved (PD15)
|
# DIG_7: reserved (PD15)
|
||||||
set_property PACKAGE_PIN H11 [get_ports {gpio_dig5}]
|
set_property PACKAGE_PIN H11 [get_ports {gpio_dig5}]
|
||||||
set_property PACKAGE_PIN G12 [get_ports {gpio_dig6}]
|
set_property PACKAGE_PIN G12 [get_ports {gpio_dig6}]
|
||||||
|
|||||||
+346
-328
@@ -1,106 +1,66 @@
|
|||||||
`timescale 1ns / 1ps
|
`timescale 1ns / 1ps
|
||||||
|
|
||||||
module ddc_400m_enhanced (
|
module ddc_400m_enhanced (
|
||||||
input wire clk_400m, // 400MHz clock from ADC DCO
|
input wire clk_400m, // 400MHz clock from ADC DCO
|
||||||
input wire clk_100m, // 100MHz system clock
|
input wire clk_100m, // 100MHz system clock
|
||||||
input wire reset_n,
|
input wire reset_n,
|
||||||
input wire mixers_enable,
|
input wire mixers_enable,
|
||||||
input wire [7:0] adc_data, // ADC data at 400MHz
|
input wire [7:0] adc_data, // ADC data at 400MHz
|
||||||
input wire adc_data_valid_i, // Valid at 400MHz
|
input wire adc_data_valid_i, // Valid at 400MHz
|
||||||
input wire adc_data_valid_q,
|
input wire adc_data_valid_q,
|
||||||
output wire signed [17:0] baseband_i,
|
output wire signed [17:0] baseband_i,
|
||||||
output wire signed [17:0] baseband_q,
|
output wire signed [17:0] baseband_q,
|
||||||
output wire baseband_valid_i,
|
output wire baseband_valid_i,
|
||||||
output wire baseband_valid_q,
|
output wire baseband_valid_q,
|
||||||
|
|
||||||
output wire [1:0] ddc_status,
|
output wire [1:0] ddc_status,
|
||||||
// Enhanced interfaces
|
// Enhanced interfaces
|
||||||
output wire [7:0] ddc_diagnostics,
|
output wire [7:0] ddc_diagnostics,
|
||||||
output wire mixer_saturation,
|
output wire mixer_saturation,
|
||||||
output wire filter_overflow,
|
output wire filter_overflow,
|
||||||
|
|
||||||
input wire [1:0] test_mode,
|
input wire [1:0] test_mode,
|
||||||
input wire [15:0] test_phase_inc,
|
input wire [15:0] test_phase_inc,
|
||||||
input wire force_saturation,
|
input wire force_saturation,
|
||||||
input wire reset_monitors,
|
input wire reset_monitors,
|
||||||
output wire [31:0] debug_sample_count,
|
output wire [31:0] debug_sample_count,
|
||||||
output wire [17:0] debug_internal_i,
|
output wire [17:0] debug_internal_i,
|
||||||
output wire [17:0] debug_internal_q
|
output wire [17:0] debug_internal_q
|
||||||
);
|
);
|
||||||
|
|
||||||
// Parameters for numerical precision
|
// Parameters for numerical precision
|
||||||
parameter ADC_WIDTH = 8;
|
parameter ADC_WIDTH = 8;
|
||||||
parameter NCO_WIDTH = 16;
|
parameter NCO_WIDTH = 16;
|
||||||
parameter MIXER_WIDTH = 18;
|
parameter MIXER_WIDTH = 18;
|
||||||
parameter OUTPUT_WIDTH = 18;
|
parameter OUTPUT_WIDTH = 18;
|
||||||
|
|
||||||
// IF frequency parameters
|
// IF frequency parameters
|
||||||
parameter IF_FREQ = 120000000;
|
parameter IF_FREQ = 120000000;
|
||||||
parameter FS = 400000000;
|
parameter FS = 400000000;
|
||||||
parameter PHASE_WIDTH = 32;
|
parameter PHASE_WIDTH = 32;
|
||||||
|
|
||||||
// Internal signals
|
// Internal signals
|
||||||
wire signed [15:0] sin_out, cos_out;
|
wire signed [15:0] sin_out, cos_out;
|
||||||
wire nco_ready;
|
wire nco_ready;
|
||||||
wire cic_valid;
|
wire cic_valid;
|
||||||
wire fir_valid;
|
wire fir_valid;
|
||||||
wire [17:0] cic_i_out, cic_q_out;
|
wire [17:0] cic_i_out, cic_q_out;
|
||||||
wire signed [17:0] fir_i_out, fir_q_out;
|
wire signed [17:0] fir_i_out, fir_q_out;
|
||||||
|
|
||||||
|
|
||||||
// Diagnostic registers
|
// Diagnostic registers
|
||||||
reg [2:0] saturation_count;
|
reg [2:0] saturation_count;
|
||||||
reg overflow_detected;
|
reg overflow_detected;
|
||||||
reg [7:0] error_counter;
|
reg [7:0] error_counter;
|
||||||
|
|
||||||
// ============================================================================
|
|
||||||
// 400 MHz Reset Synchronizer
|
|
||||||
//
|
|
||||||
// reset_n arrives from the 100 MHz domain (sys_reset_n from radar_system_top).
|
|
||||||
// Using it directly as an async reset in the 400 MHz domain causes the reset
|
|
||||||
// deassertion edge to violate timing: the 100 MHz flip-flop driving reset_n
|
|
||||||
// has its output fanning out to 1156 registers across the FPGA in the 400 MHz
|
|
||||||
// domain, requiring 18.243ns of routing (WNS = -18.081ns).
|
|
||||||
//
|
|
||||||
// Solution: 2-stage async-assert, sync-deassert reset synchronizer in the
|
|
||||||
// 400 MHz domain. Reset assertion is immediate (asynchronous — combinatorial
|
|
||||||
// path from reset_n to all 400 MHz registers). Reset deassertion is
|
|
||||||
// synchronized to clk_400m rising edge, preventing metastability.
|
|
||||||
//
|
|
||||||
// All 400 MHz submodules (NCO, CIC, mixers, LFSR) use reset_n_400m.
|
|
||||||
// All 100 MHz submodules (FIR, output stage) continue using reset_n directly
|
|
||||||
// (already synchronized to 100 MHz at radar_system_top level).
|
|
||||||
// ============================================================================
|
|
||||||
(* ASYNC_REG = "TRUE" *) reg [1:0] reset_sync_400m;
|
|
||||||
(* max_fanout = 50 *) wire reset_n_400m = reset_sync_400m[1];
|
|
||||||
|
|
||||||
// Active-high reset for DSP48E1 RST ports (avoids LUT1 inverter fan-out)
|
|
||||||
(* max_fanout = 50 *) reg reset_400m;
|
|
||||||
|
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
|
||||||
if (!reset_n) begin
|
|
||||||
reset_sync_400m <= 2'b00;
|
|
||||||
reset_400m <= 1'b1;
|
|
||||||
end else begin
|
|
||||||
reset_sync_400m <= {reset_sync_400m[0], 1'b1};
|
|
||||||
reset_400m <= ~reset_sync_400m[1];
|
|
||||||
end
|
|
||||||
end
|
|
||||||
|
|
||||||
// CDC synchronization for control signals (2-stage synchronizers)
|
|
||||||
(* ASYNC_REG = "TRUE" *) reg [1:0] mixers_enable_sync_chain;
|
|
||||||
(* ASYNC_REG = "TRUE" *) reg [1:0] force_saturation_sync_chain;
|
|
||||||
wire mixers_enable_sync;
|
|
||||||
wire force_saturation_sync;
|
|
||||||
|
|
||||||
// Debug monitoring signals
|
// Debug monitoring signals
|
||||||
reg [31:0] sample_counter;
|
reg [31:0] sample_counter;
|
||||||
wire signed [17:0] debug_mixed_i_trunc;
|
wire signed [17:0] debug_mixed_i_trunc;
|
||||||
wire signed [17:0] debug_mixed_q_trunc;
|
wire signed [17:0] debug_mixed_q_trunc;
|
||||||
|
|
||||||
// Real-time status monitoring
|
// Real-time status monitoring
|
||||||
reg [7:0] signal_power_i, signal_power_q;
|
reg [7:0] signal_power_i, signal_power_q;
|
||||||
|
|
||||||
// Internal mixing signals
|
// Internal mixing signals
|
||||||
// Pipeline: NCO fabric reg (1) + DSP48E1 AREG/BREG (1) + MREG (1) + PREG (1) + retiming (1) = 5 cycles
|
// Pipeline: NCO fabric reg (1) + DSP48E1 AREG/BREG (1) + MREG (1) + PREG (1) + retiming (1) = 5 cycles
|
||||||
// The NCO fabric pipeline register was added to break the long NCO→DSP B-port route
|
// The NCO fabric pipeline register was added to break the long NCO→DSP B-port route
|
||||||
@@ -118,61 +78,112 @@ reg [4:0] dsp_valid_pipe;
|
|||||||
// Post-DSP retiming registers — breaks DSP48E1 CLK→P to fabric timing path
|
// Post-DSP retiming registers — breaks DSP48E1 CLK→P to fabric timing path
|
||||||
// This extra pipeline stage absorbs the 1.866ns DSP output prop delay + routing,
|
// This extra pipeline stage absorbs the 1.866ns DSP output prop delay + routing,
|
||||||
// ensuring WNS > 0 at 400 MHz regardless of placement seed
|
// ensuring WNS > 0 at 400 MHz regardless of placement seed
|
||||||
(* DONT_TOUCH = "TRUE" *) reg signed [MIXER_WIDTH+NCO_WIDTH-1:0] mult_i_retimed, mult_q_retimed;
|
(* DONT_TOUCH = "TRUE" *) reg signed [MIXER_WIDTH+NCO_WIDTH-1:0] mult_i_retimed, mult_q_retimed;
|
||||||
|
|
||||||
// Output stage registers
|
// Output stage registers
|
||||||
reg signed [17:0] baseband_i_reg, baseband_q_reg;
|
reg signed [17:0] baseband_i_reg, baseband_q_reg;
|
||||||
reg baseband_valid_reg;
|
reg baseband_valid_reg;
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Phase Dithering Signals
|
// Phase Dithering Signals
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
wire [7:0] phase_dither_bits;
|
wire [7:0] phase_dither_bits;
|
||||||
reg [31:0] phase_inc_dithered;
|
reg [31:0] phase_inc_dithered;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// ============================================================================
|
|
||||||
// Debug Signal Assignments
|
|
||||||
// ============================================================================
|
|
||||||
assign debug_internal_i = mixed_i[25:8];
|
|
||||||
assign debug_internal_q = mixed_q[25:8];
|
|
||||||
assign debug_sample_count = sample_counter;
|
|
||||||
assign debug_mixed_i_trunc = mixed_i[25:8];
|
|
||||||
assign debug_mixed_q_trunc = mixed_q[25:8];
|
|
||||||
|
|
||||||
// ============================================================================
|
|
||||||
// Clock Domain Crossing for Control Signals (2-stage synchronizers)
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
|
// Debug Signal Assignments
|
||||||
|
// ============================================================================
|
||||||
|
assign debug_internal_i = mixed_i[25:8];
|
||||||
|
assign debug_internal_q = mixed_q[25:8];
|
||||||
|
assign debug_sample_count = sample_counter;
|
||||||
|
assign debug_mixed_i_trunc = mixed_i[25:8];
|
||||||
|
assign debug_mixed_q_trunc = mixed_q[25:8];
|
||||||
|
|
||||||
|
// ============================================================================
|
||||||
|
// 400 MHz Reset Synchronizer
|
||||||
|
//
|
||||||
|
// reset_n arrives from the 100 MHz domain (sys_reset_n from radar_system_top).
|
||||||
|
// Using it directly as an async reset in the 400 MHz domain causes the reset
|
||||||
|
// deassertion edge to violate timing: the 100 MHz flip-flop driving reset_n
|
||||||
|
// has its output fanning out to 1156 registers across the FPGA in the 400 MHz
|
||||||
|
// domain, requiring 18.243ns of routing (WNS = -18.081ns).
|
||||||
|
//
|
||||||
|
// Solution: 2-stage async-assert, sync-deassert reset synchronizer in the
|
||||||
|
// 400 MHz domain. Reset assertion is immediate (asynchronous — combinatorial
|
||||||
|
// path from reset_n to all 400 MHz registers). Reset deassertion is
|
||||||
|
//
|
||||||
|
// reset_400m : ACTIVE-HIGH registered reset with (* max_fanout = 50 *).
|
||||||
|
// This is THE signal fed to every synchronous 400 MHz FDRE
|
||||||
|
// and every DSP48E1 RST pin in this module and its children
|
||||||
|
// (NCO, CIC, LFSR). Vivado replicates the register (~14
|
||||||
|
// copies) so each replica drives ≈50 loads regionally,
|
||||||
|
// eliminating the single-LUT1 / 702-load net that caused
|
||||||
|
// WNS=-0.626 ns in Build N.
|
||||||
|
//
|
||||||
|
// System-level invariants preserved:
|
||||||
|
// I1 Reset assertion propagates to all 400 MHz regs within ≤3 clk edges
|
||||||
|
// (2 sync + 1 replicated-reg fanout). At 400 MHz = 7.5 ns << any
|
||||||
|
// system-level reset assertion duration.
|
||||||
|
// I2 Reset de-assertion is always synchronous to clk_400m (via
|
||||||
|
// reset_sync_400m), never glitches.
|
||||||
|
// I3 DSP48E1 RST pins are all fed from Q of a register — glitch-free.
|
||||||
|
// I4 No new CDC introduced: reset_400m is entirely in clk_400m domain.
|
||||||
|
// I5 Power-up: reset_n is asserted externally and mmcm_locked is low;
|
||||||
|
// reset_sync_400m stays 2'b00, reset_400m stays 1'b1, downstream
|
||||||
|
// FDREs stay cleared. Safe.
|
||||||
|
// ============================================================================
|
||||||
|
(* ASYNC_REG = "TRUE" *) reg [1:0] reset_sync_400m = 2'b00;
|
||||||
|
(* max_fanout = 50 *) wire reset_n_400m = reset_sync_400m[1];
|
||||||
|
|
||||||
|
// Active-high replicated reset for all synchronous 400 MHz consumers
|
||||||
|
(* max_fanout = 50 *) reg reset_400m = 1'b1;
|
||||||
|
|
||||||
|
always @(posedge clk_400m or negedge reset_n) begin
|
||||||
|
if (!reset_n) begin
|
||||||
|
reset_sync_400m <= 2'b00;
|
||||||
|
reset_400m <= 1'b1;
|
||||||
|
end else begin
|
||||||
|
reset_sync_400m <= {reset_sync_400m[0], 1'b1};
|
||||||
|
reset_400m <= ~reset_sync_400m[1];
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
// CDC synchronization for control signals (2-stage synchronizers)
|
||||||
|
(* ASYNC_REG = "TRUE" *) reg [1:0] mixers_enable_sync_chain;
|
||||||
|
(* ASYNC_REG = "TRUE" *) reg [1:0] force_saturation_sync_chain;
|
||||||
|
wire mixers_enable_sync;
|
||||||
|
wire force_saturation_sync;
|
||||||
assign mixers_enable_sync = mixers_enable_sync_chain[1];
|
assign mixers_enable_sync = mixers_enable_sync_chain[1];
|
||||||
assign force_saturation_sync = force_saturation_sync_chain[1];
|
assign force_saturation_sync = force_saturation_sync_chain[1];
|
||||||
|
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
// Sync reset via reset_400m (replicated, max_fanout=50). Was async on
|
||||||
if (!reset_n_400m) begin
|
// reset_n_400m — see "400 MHz RESET DISTRIBUTION" comment above.
|
||||||
|
always @(posedge clk_400m) begin
|
||||||
|
if (reset_400m) begin
|
||||||
mixers_enable_sync_chain <= 2'b00;
|
mixers_enable_sync_chain <= 2'b00;
|
||||||
force_saturation_sync_chain <= 2'b00;
|
force_saturation_sync_chain <= 2'b00;
|
||||||
end else begin
|
end else begin
|
||||||
mixers_enable_sync_chain <= {mixers_enable_sync_chain[0], mixers_enable};
|
mixers_enable_sync_chain <= {mixers_enable_sync_chain[0], mixers_enable};
|
||||||
force_saturation_sync_chain <= {force_saturation_sync_chain[0], force_saturation};
|
force_saturation_sync_chain <= {force_saturation_sync_chain[0], force_saturation};
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Sample Counter and Debug Monitoring
|
// Sample Counter and Debug Monitoring
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m || reset_monitors) begin
|
if (reset_400m || reset_monitors) begin
|
||||||
sample_counter <= 0;
|
sample_counter <= 0;
|
||||||
error_counter <= 0;
|
error_counter <= 0;
|
||||||
end else if (adc_data_valid_i && adc_data_valid_q ) begin
|
end else if (adc_data_valid_i && adc_data_valid_q ) begin
|
||||||
sample_counter <= sample_counter + 1;
|
sample_counter <= sample_counter + 1;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced Phase Dithering Instance
|
// Enhanced Phase Dithering Instance
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
lfsr_dither_enhanced #(
|
lfsr_dither_enhanced #(
|
||||||
.DITHER_WIDTH(8)
|
.DITHER_WIDTH(8)
|
||||||
) phase_dither_gen (
|
) phase_dither_gen (
|
||||||
@@ -180,36 +191,36 @@ lfsr_dither_enhanced #(
|
|||||||
.reset_n(reset_n_400m),
|
.reset_n(reset_n_400m),
|
||||||
.enable(nco_ready),
|
.enable(nco_ready),
|
||||||
.dither_out(phase_dither_bits)
|
.dither_out(phase_dither_bits)
|
||||||
);
|
);
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Phase Increment Calculation with Dithering
|
// Phase Increment Calculation with Dithering
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Calculate phase increment for 120MHz IF at 400MHz sampling
|
// Calculate phase increment for 120MHz IF at 400MHz sampling
|
||||||
localparam PHASE_INC_120MHZ = 32'h4CCCCCCD;
|
localparam PHASE_INC_120MHZ = 32'h4CCCCCCD;
|
||||||
|
|
||||||
// Apply dithering to reduce spurious tones (registered for 400 MHz timing)
|
// Apply dithering to reduce spurious tones (registered for 400 MHz timing)
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m)
|
if (reset_400m)
|
||||||
phase_inc_dithered <= PHASE_INC_120MHZ;
|
phase_inc_dithered <= PHASE_INC_120MHZ;
|
||||||
else
|
else
|
||||||
phase_inc_dithered <= PHASE_INC_120MHZ + {24'b0, phase_dither_bits};
|
phase_inc_dithered <= PHASE_INC_120MHZ + {24'b0, phase_dither_bits};
|
||||||
end
|
end
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced NCO with Diagnostics
|
// Enhanced NCO with Diagnostics
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
nco_400m_enhanced nco_core (
|
nco_400m_enhanced nco_core (
|
||||||
.clk_400m(clk_400m),
|
.clk_400m(clk_400m),
|
||||||
.reset_n(reset_n_400m),
|
.reset_n(reset_n_400m),
|
||||||
.frequency_tuning_word(phase_inc_dithered),
|
.frequency_tuning_word(phase_inc_dithered),
|
||||||
.phase_valid(mixers_enable),
|
.phase_valid(mixers_enable),
|
||||||
.phase_offset(16'h0000),
|
.phase_offset(16'h0000),
|
||||||
.sin_out(sin_out),
|
.sin_out(sin_out),
|
||||||
.cos_out(cos_out),
|
.cos_out(cos_out),
|
||||||
.dds_ready(nco_ready)
|
.dds_ready(nco_ready)
|
||||||
);
|
);
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced Mixing Stage — DSP48E1 direct instantiation for 400 MHz timing
|
// Enhanced Mixing Stage — DSP48E1 direct instantiation for 400 MHz timing
|
||||||
//
|
//
|
||||||
@@ -229,8 +240,8 @@ assign adc_signed_w = {1'b0, adc_data, {(MIXER_WIDTH-ADC_WIDTH-1){1'b0}}} -
|
|||||||
{1'b0, {ADC_WIDTH{1'b1}}, {(MIXER_WIDTH-ADC_WIDTH-1){1'b0}}} / 2;
|
{1'b0, {ADC_WIDTH{1'b1}}, {(MIXER_WIDTH-ADC_WIDTH-1){1'b0}}} / 2;
|
||||||
|
|
||||||
// Valid pipeline: 5-stage shift register (1 NCO pipe + 3 DSP48E1 AREG+MREG+PREG + 1 retiming)
|
// Valid pipeline: 5-stage shift register (1 NCO pipe + 3 DSP48E1 AREG+MREG+PREG + 1 retiming)
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
dsp_valid_pipe <= 5'b00000;
|
dsp_valid_pipe <= 5'b00000;
|
||||||
end else begin
|
end else begin
|
||||||
dsp_valid_pipe <= {dsp_valid_pipe[3:0], (nco_ready && adc_data_valid_i && adc_data_valid_q)};
|
dsp_valid_pipe <= {dsp_valid_pipe[3:0], (nco_ready && adc_data_valid_i && adc_data_valid_q)};
|
||||||
@@ -246,8 +257,8 @@ reg signed [MIXER_WIDTH+NCO_WIDTH-1:0] mult_i_internal, mult_q_internal; // Mod
|
|||||||
reg signed [MIXER_WIDTH+NCO_WIDTH-1:0] mult_i_reg, mult_q_reg; // Models PREG
|
reg signed [MIXER_WIDTH+NCO_WIDTH-1:0] mult_i_reg, mult_q_reg; // Models PREG
|
||||||
|
|
||||||
// Stage 0: NCO pipeline — breaks long NCO→DSP route (matches synthesis fabric registers)
|
// Stage 0: NCO pipeline — breaks long NCO→DSP route (matches synthesis fabric registers)
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
cos_nco_pipe <= 0;
|
cos_nco_pipe <= 0;
|
||||||
sin_nco_pipe <= 0;
|
sin_nco_pipe <= 0;
|
||||||
end else begin
|
end else begin
|
||||||
@@ -257,8 +268,8 @@ always @(posedge clk_400m or negedge reset_n_400m) begin
|
|||||||
end
|
end
|
||||||
|
|
||||||
// Stage 1: AREG/BREG equivalent (uses pipelined NCO outputs)
|
// Stage 1: AREG/BREG equivalent (uses pipelined NCO outputs)
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
adc_signed_reg <= 0;
|
adc_signed_reg <= 0;
|
||||||
cos_pipe_reg <= 0;
|
cos_pipe_reg <= 0;
|
||||||
sin_pipe_reg <= 0;
|
sin_pipe_reg <= 0;
|
||||||
@@ -270,8 +281,8 @@ always @(posedge clk_400m or negedge reset_n_400m) begin
|
|||||||
end
|
end
|
||||||
|
|
||||||
// Stage 2: MREG equivalent
|
// Stage 2: MREG equivalent
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
mult_i_internal <= 0;
|
mult_i_internal <= 0;
|
||||||
mult_q_internal <= 0;
|
mult_q_internal <= 0;
|
||||||
end else begin
|
end else begin
|
||||||
@@ -281,8 +292,8 @@ always @(posedge clk_400m or negedge reset_n_400m) begin
|
|||||||
end
|
end
|
||||||
|
|
||||||
// Stage 3: PREG equivalent
|
// Stage 3: PREG equivalent
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
mult_i_reg <= 0;
|
mult_i_reg <= 0;
|
||||||
mult_q_reg <= 0;
|
mult_q_reg <= 0;
|
||||||
end else begin
|
end else begin
|
||||||
@@ -292,8 +303,8 @@ always @(posedge clk_400m or negedge reset_n_400m) begin
|
|||||||
end
|
end
|
||||||
|
|
||||||
// Stage 4: Post-DSP retiming register (matches synthesis path)
|
// Stage 4: Post-DSP retiming register (matches synthesis path)
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
mult_i_retimed <= 0;
|
mult_i_retimed <= 0;
|
||||||
mult_q_retimed <= 0;
|
mult_q_retimed <= 0;
|
||||||
end else begin
|
end else begin
|
||||||
@@ -311,8 +322,8 @@ wire [47:0] dsp_p_i, dsp_p_q;
|
|||||||
// (1.505ns routing observed in Build 26). These fabric registers are placed
|
// (1.505ns routing observed in Build 26). These fabric registers are placed
|
||||||
// near the DSP by the placer, splitting the route into two shorter segments.
|
// near the DSP by the placer, splitting the route into two shorter segments.
|
||||||
// DONT_TOUCH on the reg declaration (above) prevents absorption/retiming.
|
// DONT_TOUCH on the reg declaration (above) prevents absorption/retiming.
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
cos_nco_pipe <= 0;
|
cos_nco_pipe <= 0;
|
||||||
sin_nco_pipe <= 0;
|
sin_nco_pipe <= 0;
|
||||||
end else begin
|
end else begin
|
||||||
@@ -329,11 +340,10 @@ DSP48E1 #(
|
|||||||
.USE_DPORT("FALSE"),
|
.USE_DPORT("FALSE"),
|
||||||
.USE_MULT("MULTIPLY"),
|
.USE_MULT("MULTIPLY"),
|
||||||
.USE_SIMD("ONE48"),
|
.USE_SIMD("ONE48"),
|
||||||
// Pipeline register attributes — all enabled for max timing
|
|
||||||
.AREG(1),
|
.AREG(1),
|
||||||
.BREG(1),
|
.BREG(1),
|
||||||
.MREG(1),
|
.MREG(1),
|
||||||
.PREG(1), // P register enabled — absorbs CLK→P delay for timing closure
|
.PREG(1),
|
||||||
.ADREG(0),
|
.ADREG(0),
|
||||||
.ACASCREG(1),
|
.ACASCREG(1),
|
||||||
.BCASCREG(1),
|
.BCASCREG(1),
|
||||||
@@ -344,7 +354,6 @@ DSP48E1 #(
|
|||||||
.DREG(0),
|
.DREG(0),
|
||||||
.INMODEREG(0),
|
.INMODEREG(0),
|
||||||
.OPMODEREG(0),
|
.OPMODEREG(0),
|
||||||
// Pattern detector (unused)
|
|
||||||
.AUTORESET_PATDET("NO_RESET"),
|
.AUTORESET_PATDET("NO_RESET"),
|
||||||
.MASK(48'h3fffffffffff),
|
.MASK(48'h3fffffffffff),
|
||||||
.PATTERN(48'h000000000000),
|
.PATTERN(48'h000000000000),
|
||||||
@@ -496,8 +505,8 @@ wire signed [MIXER_WIDTH+NCO_WIDTH-1:0] mult_q_reg = dsp_p_q[MIXER_WIDTH+NCO_WID
|
|||||||
// Stage 4: Post-DSP retiming register — breaks DSP48E1 CLK→P to fabric path
|
// Stage 4: Post-DSP retiming register — breaks DSP48E1 CLK→P to fabric path
|
||||||
// Without this, the DSP output prop delay (1.866ns) + routing (0.515ns) exceeds
|
// Without this, the DSP output prop delay (1.866ns) + routing (0.515ns) exceeds
|
||||||
// the 2.500ns clock period at slow process corner
|
// the 2.500ns clock period at slow process corner
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
mult_i_retimed <= 0;
|
mult_i_retimed <= 0;
|
||||||
mult_q_retimed <= 0;
|
mult_q_retimed <= 0;
|
||||||
end else begin
|
end else begin
|
||||||
@@ -513,8 +522,8 @@ end
|
|||||||
// force_saturation mux is intentionally AFTER the DSP48E1 output to avoid
|
// force_saturation mux is intentionally AFTER the DSP48E1 output to avoid
|
||||||
// polluting the critical input path with extra logic
|
// polluting the critical input path with extra logic
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n_400m) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n_400m) begin
|
if (reset_400m) begin
|
||||||
mixed_i <= 0;
|
mixed_i <= 0;
|
||||||
mixed_q <= 0;
|
mixed_q <= 0;
|
||||||
mixed_valid <= 0;
|
mixed_valid <= 0;
|
||||||
@@ -556,31 +565,31 @@ always @(posedge clk_400m or negedge reset_n_400m) begin
|
|||||||
mixer_overflow_q <= 0;
|
mixer_overflow_q <= 0;
|
||||||
overflow_detected <= 1'b0;
|
overflow_detected <= 1'b0;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced CIC Decimators
|
// Enhanced CIC Decimators
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
wire cic_valid_i, cic_valid_q;
|
wire cic_valid_i, cic_valid_q;
|
||||||
|
|
||||||
cic_decimator_4x_enhanced cic_i_inst (
|
cic_decimator_4x_enhanced cic_i_inst (
|
||||||
.clk(clk_400m),
|
.clk(clk_400m),
|
||||||
.reset_n(reset_n_400m),
|
.reset_n(reset_n_400m),
|
||||||
.data_in(mixed_i[33:16]),
|
.data_in(mixed_i[33:16]),
|
||||||
.data_valid(mixed_valid),
|
.data_valid(mixed_valid),
|
||||||
.data_out(cic_i_out),
|
.data_out(cic_i_out),
|
||||||
.data_out_valid(cic_valid_i)
|
.data_out_valid(cic_valid_i)
|
||||||
);
|
);
|
||||||
|
|
||||||
cic_decimator_4x_enhanced cic_q_inst (
|
cic_decimator_4x_enhanced cic_q_inst (
|
||||||
.clk(clk_400m),
|
.clk(clk_400m),
|
||||||
.reset_n(reset_n_400m),
|
.reset_n(reset_n_400m),
|
||||||
.data_in(mixed_q[33:16]),
|
.data_in(mixed_q[33:16]),
|
||||||
.data_valid(mixed_valid),
|
.data_valid(mixed_valid),
|
||||||
.data_out(cic_q_out),
|
.data_out(cic_q_out),
|
||||||
.data_out_valid(cic_valid_q)
|
.data_out_valid(cic_valid_q)
|
||||||
);
|
);
|
||||||
|
|
||||||
assign cic_valid = cic_valid_i & cic_valid_q;
|
assign cic_valid = cic_valid_i & cic_valid_q;
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
@@ -593,96 +602,96 @@ wire fir_valid_i, fir_valid_q;
|
|||||||
wire fir_i_ready, fir_q_ready;
|
wire fir_i_ready, fir_q_ready;
|
||||||
wire [17:0] fir_d_in_i, fir_d_in_q;
|
wire [17:0] fir_d_in_i, fir_d_in_q;
|
||||||
|
|
||||||
cdc_adc_to_processing #(
|
cdc_adc_to_processing #(
|
||||||
.WIDTH(18),
|
.WIDTH(18),
|
||||||
.STAGES(3)
|
.STAGES(3)
|
||||||
)CDC_FIR_i(
|
)CDC_FIR_i(
|
||||||
.src_clk(clk_400m),
|
.src_clk(clk_400m),
|
||||||
.dst_clk(clk_100m),
|
.dst_clk(clk_100m),
|
||||||
.src_reset_n(reset_n_400m),
|
.src_reset_n(reset_n_400m),
|
||||||
.dst_reset_n(reset_n),
|
.dst_reset_n(reset_n),
|
||||||
.src_data(cic_i_out),
|
.src_data(cic_i_out),
|
||||||
.src_valid(cic_valid_i),
|
.src_valid(cic_valid_i),
|
||||||
.dst_data(fir_d_in_i),
|
.dst_data(fir_d_in_i),
|
||||||
.dst_valid(fir_in_valid_i)
|
.dst_valid(fir_in_valid_i)
|
||||||
);
|
);
|
||||||
|
|
||||||
cdc_adc_to_processing #(
|
cdc_adc_to_processing #(
|
||||||
.WIDTH(18),
|
.WIDTH(18),
|
||||||
.STAGES(3)
|
.STAGES(3)
|
||||||
)CDC_FIR_q(
|
)CDC_FIR_q(
|
||||||
.src_clk(clk_400m),
|
.src_clk(clk_400m),
|
||||||
.dst_clk(clk_100m),
|
.dst_clk(clk_100m),
|
||||||
.src_reset_n(reset_n_400m),
|
.src_reset_n(reset_n_400m),
|
||||||
.dst_reset_n(reset_n),
|
.dst_reset_n(reset_n),
|
||||||
.src_data(cic_q_out),
|
.src_data(cic_q_out),
|
||||||
.src_valid(cic_valid_q),
|
.src_valid(cic_valid_q),
|
||||||
.dst_data(fir_d_in_q),
|
.dst_data(fir_d_in_q),
|
||||||
.dst_valid(fir_in_valid_q)
|
.dst_valid(fir_in_valid_q)
|
||||||
);
|
);
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// FIR Filter Instances
|
// FIR Filter Instances
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
|
|
||||||
// FIR I channel
|
// FIR I channel
|
||||||
fir_lowpass_parallel_enhanced fir_i_inst (
|
fir_lowpass_parallel_enhanced fir_i_inst (
|
||||||
.clk(clk_100m),
|
.clk(clk_100m),
|
||||||
.reset_n(reset_n),
|
.reset_n(reset_n),
|
||||||
.data_in(fir_d_in_i), // Use synchronized data
|
.data_in(fir_d_in_i), // Use synchronized data
|
||||||
.data_valid(fir_in_valid_i), // Use synchronized valid
|
.data_valid(fir_in_valid_i), // Use synchronized valid
|
||||||
.data_out(fir_i_out),
|
.data_out(fir_i_out),
|
||||||
.data_out_valid(fir_valid_i),
|
.data_out_valid(fir_valid_i),
|
||||||
.fir_ready(fir_i_ready),
|
.fir_ready(fir_i_ready),
|
||||||
.filter_overflow()
|
.filter_overflow()
|
||||||
);
|
);
|
||||||
|
|
||||||
// FIR Q channel
|
// FIR Q channel
|
||||||
fir_lowpass_parallel_enhanced fir_q_inst (
|
fir_lowpass_parallel_enhanced fir_q_inst (
|
||||||
.clk(clk_100m),
|
.clk(clk_100m),
|
||||||
.reset_n(reset_n),
|
.reset_n(reset_n),
|
||||||
.data_in(fir_d_in_q), // Use synchronized data
|
.data_in(fir_d_in_q), // Use synchronized data
|
||||||
.data_valid(fir_in_valid_q), // Use synchronized valid
|
.data_valid(fir_in_valid_q), // Use synchronized valid
|
||||||
.data_out(fir_q_out),
|
.data_out(fir_q_out),
|
||||||
.data_out_valid(fir_valid_q),
|
.data_out_valid(fir_valid_q),
|
||||||
.fir_ready(fir_q_ready),
|
.fir_ready(fir_q_ready),
|
||||||
.filter_overflow()
|
.filter_overflow()
|
||||||
);
|
);
|
||||||
|
|
||||||
assign fir_valid = fir_valid_i & fir_valid_q;
|
assign fir_valid = fir_valid_i & fir_valid_q;
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced Output Stage
|
// Enhanced Output Stage
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_100m or negedge reset_n) begin
|
always @(posedge clk_100m or negedge reset_n) begin
|
||||||
if (!reset_n) begin
|
if (!reset_n) begin
|
||||||
baseband_i_reg <= 0;
|
baseband_i_reg <= 0;
|
||||||
baseband_q_reg <= 0;
|
baseband_q_reg <= 0;
|
||||||
baseband_valid_reg <= 0;
|
baseband_valid_reg <= 0;
|
||||||
end else if (fir_valid) begin
|
end else if (fir_valid) begin
|
||||||
baseband_i_reg <= fir_i_out;
|
baseband_i_reg <= fir_i_out;
|
||||||
baseband_q_reg <= fir_q_out;
|
baseband_q_reg <= fir_q_out;
|
||||||
baseband_valid_reg <= 1;
|
baseband_valid_reg <= 1;
|
||||||
end else begin
|
end else begin
|
||||||
baseband_valid_reg <= 0;
|
baseband_valid_reg <= 0;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Output Assignments
|
// Output Assignments
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
assign baseband_i = baseband_i_reg;
|
assign baseband_i = baseband_i_reg;
|
||||||
assign baseband_q = baseband_q_reg;
|
assign baseband_q = baseband_q_reg;
|
||||||
assign baseband_valid_i = baseband_valid_reg;
|
assign baseband_valid_i = baseband_valid_reg;
|
||||||
assign baseband_valid_q = baseband_valid_reg;
|
assign baseband_valid_q = baseband_valid_reg;
|
||||||
assign ddc_status = {mixer_overflow_i | mixer_overflow_q, nco_ready};
|
assign ddc_status = {mixer_overflow_i | mixer_overflow_q, nco_ready};
|
||||||
assign mixer_saturation = overflow_detected;
|
assign mixer_saturation = overflow_detected;
|
||||||
assign ddc_diagnostics = {saturation_count, error_counter[4:0]};
|
assign ddc_diagnostics = {saturation_count, error_counter[4:0]};
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced Debug and Monitoring
|
// Enhanced Debug and Monitoring
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
reg [31:0] debug_cic_count, debug_fir_count, debug_bb_count;
|
reg [31:0] debug_cic_count, debug_fir_count, debug_bb_count;
|
||||||
|
|
||||||
`ifdef SIMULATION
|
`ifdef SIMULATION
|
||||||
@@ -699,10 +708,10 @@ always @(posedge clk_100m) begin
|
|||||||
baseband_i, baseband_q, debug_bb_count);
|
baseband_i, baseband_q, debug_bb_count);
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
`endif
|
`endif
|
||||||
|
|
||||||
// In ddc_400m.v, add these debug signals:
|
// In ddc_400m.v, add these debug signals:
|
||||||
|
|
||||||
// Debug monitoring (simulation only)
|
// Debug monitoring (simulation only)
|
||||||
`ifdef SIMULATION
|
`ifdef SIMULATION
|
||||||
reg [31:0] debug_adc_count = 0;
|
reg [31:0] debug_adc_count = 0;
|
||||||
@@ -723,58 +732,67 @@ always @(posedge clk_100m) begin
|
|||||||
baseband_i, baseband_q, debug_baseband_count, $time);
|
baseband_i, baseband_q, debug_baseband_count, $time);
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
`endif
|
`endif
|
||||||
|
|
||||||
|
|
||||||
endmodule
|
endmodule
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Enhanced Phase Dithering Module
|
// Enhanced Phase Dithering Module
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
`timescale 1ns / 1ps
|
`timescale 1ns / 1ps
|
||||||
|
|
||||||
module lfsr_dither_enhanced #(
|
module lfsr_dither_enhanced #(
|
||||||
parameter DITHER_WIDTH = 8 // Increased for better dithering
|
parameter DITHER_WIDTH = 8 // Increased for better dithering
|
||||||
)(
|
)(
|
||||||
input wire clk,
|
input wire clk,
|
||||||
input wire reset_n,
|
input wire reset_n,
|
||||||
input wire enable,
|
input wire enable,
|
||||||
output wire [DITHER_WIDTH-1:0] dither_out
|
output wire [DITHER_WIDTH-1:0] dither_out
|
||||||
);
|
);
|
||||||
|
|
||||||
reg [DITHER_WIDTH-1:0] lfsr_reg;
|
reg [DITHER_WIDTH-1:0] lfsr_reg;
|
||||||
reg [15:0] cycle_counter;
|
reg [15:0] cycle_counter;
|
||||||
reg lock_detected;
|
reg lock_detected;
|
||||||
|
|
||||||
// Polynomial for better randomness: x^8 + x^6 + x^5 + x^4 + 1
|
// Polynomial for better randomness: x^8 + x^6 + x^5 + x^4 + 1
|
||||||
wire feedback;
|
wire feedback;
|
||||||
|
|
||||||
generate
|
generate
|
||||||
if (DITHER_WIDTH == 4) begin
|
if (DITHER_WIDTH == 4) begin
|
||||||
assign feedback = lfsr_reg[3] ^ lfsr_reg[2];
|
assign feedback = lfsr_reg[3] ^ lfsr_reg[2];
|
||||||
end else if (DITHER_WIDTH == 8) begin
|
end else if (DITHER_WIDTH == 8) begin
|
||||||
assign feedback = lfsr_reg[7] ^ lfsr_reg[5] ^ lfsr_reg[4] ^ lfsr_reg[3];
|
assign feedback = lfsr_reg[7] ^ lfsr_reg[5] ^ lfsr_reg[4] ^ lfsr_reg[3];
|
||||||
end else begin
|
end else begin
|
||||||
assign feedback = lfsr_reg[DITHER_WIDTH-1] ^ lfsr_reg[DITHER_WIDTH-2];
|
assign feedback = lfsr_reg[DITHER_WIDTH-1] ^ lfsr_reg[DITHER_WIDTH-2];
|
||||||
end
|
end
|
||||||
endgenerate
|
endgenerate
|
||||||
|
|
||||||
always @(posedge clk or negedge reset_n) begin
|
// ============================================================================
|
||||||
if (!reset_n) begin
|
// RESET FAN-OUT INVARIANT: registered active-high reset with max_fanout=50.
|
||||||
lfsr_reg <= {DITHER_WIDTH{1'b1}}; // Non-zero initial state
|
// See cic_decimator_4x_enhanced.v for full reasoning. reset_n here is driven
|
||||||
cycle_counter <= 0;
|
// by the parent DDC's reset_n_400m (already synchronized to clk_400m), so
|
||||||
lock_detected <= 0;
|
// sync reset on the LFSR is safe. INIT=1'b1 holds LFSR in reset on power-up.
|
||||||
end else if (enable) begin
|
// ============================================================================
|
||||||
lfsr_reg <= {lfsr_reg[DITHER_WIDTH-2:0], feedback};
|
(* max_fanout = 50 *) reg reset_h = 1'b1;
|
||||||
cycle_counter <= cycle_counter + 1;
|
always @(posedge clk) reset_h <= ~reset_n;
|
||||||
|
|
||||||
// Detect LFSR lock after sufficient cycles
|
always @(posedge clk) begin
|
||||||
if (cycle_counter > (2**DITHER_WIDTH * 8)) begin
|
if (reset_h) begin
|
||||||
lock_detected <= 1'b1;
|
lfsr_reg <= {DITHER_WIDTH{1'b1}}; // Non-zero initial state
|
||||||
end
|
cycle_counter <= 0;
|
||||||
end
|
lock_detected <= 0;
|
||||||
end
|
end else if (enable) begin
|
||||||
|
lfsr_reg <= {lfsr_reg[DITHER_WIDTH-2:0], feedback};
|
||||||
assign dither_out = lfsr_reg;
|
cycle_counter <= cycle_counter + 1;
|
||||||
|
|
||||||
endmodule
|
// Detect LFSR lock after sufficient cycles
|
||||||
|
if (cycle_counter > (2**DITHER_WIDTH * 8)) begin
|
||||||
|
lock_detected <= 1'b1;
|
||||||
|
end
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
assign dither_out = lfsr_reg;
|
||||||
|
|
||||||
|
endmodule
|
||||||
|
|||||||
@@ -59,6 +59,25 @@ reg [1:0] quadrant_reg2; // Pass-through for Stage 5 MUX
|
|||||||
// Valid pipeline: tracks 6-stage latency
|
// Valid pipeline: tracks 6-stage latency
|
||||||
reg [5:0] valid_pipe;
|
reg [5:0] valid_pipe;
|
||||||
|
|
||||||
|
// ============================================================================
|
||||||
|
// RESET FAN-OUT INVARIANT (Build N+1 fix for WNS=-0.626ns at 400 MHz):
|
||||||
|
// ============================================================================
|
||||||
|
// reset_h is an ACTIVE-HIGH, REGISTERED copy of ~reset_n with (* max_fanout=50 *).
|
||||||
|
// Vivado replicates this register (14+ copies) so each copy drives ≈50 loads
|
||||||
|
// regionally, avoiding the single-LUT1 / 702-load net that caused timing
|
||||||
|
// failure in Build N. It feeds:
|
||||||
|
// - DSP48E1 RSTP/RSTC on the phase-accumulator DSP (below)
|
||||||
|
// - All pipeline-stage fabric FDREs (synchronous reset)
|
||||||
|
// Invariants (see cic_decimator_4x_enhanced.v for full reasoning):
|
||||||
|
// I1 correctness: reset_h == ~reset_n one cycle later
|
||||||
|
// I2 glitch-free: registered output
|
||||||
|
// I3 power-up safe: INIT=1'b1 holds all downstream in reset until first
|
||||||
|
// valid clock edge; reset_n is low on power-up anyway
|
||||||
|
// I4 de-assert lat.: +1 cycle vs. direct async; negligible at 400 MHz
|
||||||
|
// ============================================================================
|
||||||
|
(* max_fanout = 50 *) reg reset_h = 1'b1;
|
||||||
|
always @(posedge clk_400m) reset_h <= ~reset_n;
|
||||||
|
|
||||||
// Use only the top 8 bits for LUT addressing (256-entry LUT equivalent)
|
// Use only the top 8 bits for LUT addressing (256-entry LUT equivalent)
|
||||||
wire [7:0] lut_address = phase_with_offset[31:24];
|
wire [7:0] lut_address = phase_with_offset[31:24];
|
||||||
|
|
||||||
@@ -135,8 +154,8 @@ wire [15:0] cos_abs_w = sin_lut[63 - lut_index_pipe_cos];
|
|||||||
// Stage 2: phase_with_offset adds phase offset
|
// Stage 2: phase_with_offset adds phase offset
|
||||||
reg [31:0] phase_accumulator;
|
reg [31:0] phase_accumulator;
|
||||||
|
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
phase_accumulator <= 32'h00000000;
|
phase_accumulator <= 32'h00000000;
|
||||||
phase_accum_reg <= 32'h00000000;
|
phase_accum_reg <= 32'h00000000;
|
||||||
phase_with_offset <= 32'h00000000;
|
phase_with_offset <= 32'h00000000;
|
||||||
@@ -190,8 +209,8 @@ DSP48E1 #(
|
|||||||
.RSTA(1'b0),
|
.RSTA(1'b0),
|
||||||
.RSTB(1'b0),
|
.RSTB(1'b0),
|
||||||
.RSTM(1'b0),
|
.RSTM(1'b0),
|
||||||
.RSTP(!reset_n), // Reset P register (phase accumulator) on !reset_n
|
.RSTP(reset_h), // Reset P register (phase accumulator) — registered, max_fanout=50
|
||||||
.RSTC(!reset_n), // Reset C register (tuning word) on !reset_n
|
.RSTC(reset_h), // Reset C register (tuning word) — registered, max_fanout=50
|
||||||
.RSTALLCARRYIN(1'b0),
|
.RSTALLCARRYIN(1'b0),
|
||||||
.RSTALUMODE(1'b0),
|
.RSTALUMODE(1'b0),
|
||||||
.RSTCTRL(1'b0),
|
.RSTCTRL(1'b0),
|
||||||
@@ -245,8 +264,8 @@ DSP48E1 #(
|
|||||||
// Stage 1: Capture DSP48E1 P output into fabric register
|
// Stage 1: Capture DSP48E1 P output into fabric register
|
||||||
// Stage 2: Add phase offset to captured value
|
// Stage 2: Add phase offset to captured value
|
||||||
// Split into two registered stages to break DSP48E1.P→CARRY4 critical path
|
// Split into two registered stages to break DSP48E1.P→CARRY4 critical path
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
phase_accum_reg <= 32'h00000000;
|
phase_accum_reg <= 32'h00000000;
|
||||||
phase_with_offset <= 32'h00000000;
|
phase_with_offset <= 32'h00000000;
|
||||||
end else if (phase_valid) begin
|
end else if (phase_valid) begin
|
||||||
@@ -264,8 +283,8 @@ end
|
|||||||
// Only 2 registers driven (lut_index_pipe + quadrant_pipe)
|
// Only 2 registers driven (lut_index_pipe + quadrant_pipe)
|
||||||
// Minimal fanout → short routes → easy timing
|
// Minimal fanout → short routes → easy timing
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
lut_index_pipe_sin <= 6'b000000;
|
lut_index_pipe_sin <= 6'b000000;
|
||||||
lut_index_pipe_cos <= 6'b000000;
|
lut_index_pipe_cos <= 6'b000000;
|
||||||
quadrant_pipe <= 2'b00;
|
quadrant_pipe <= 2'b00;
|
||||||
@@ -281,8 +300,8 @@ end
|
|||||||
// Registered address → combinational LUT6 read → register
|
// Registered address → combinational LUT6 read → register
|
||||||
// Only 1 logic level (LUT6), trivial timing
|
// Only 1 logic level (LUT6), trivial timing
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
sin_abs_reg <= 16'h0000;
|
sin_abs_reg <= 16'h0000;
|
||||||
cos_abs_reg <= 16'h7FFF;
|
cos_abs_reg <= 16'h7FFF;
|
||||||
quadrant_reg <= 2'b00;
|
quadrant_reg <= 2'b00;
|
||||||
@@ -298,8 +317,8 @@ end
|
|||||||
// CARRY4 x4 chain has registered inputs — easily fits in 2.5ns
|
// CARRY4 x4 chain has registered inputs — easily fits in 2.5ns
|
||||||
// Also pass through abs values and quadrant for Stage 5
|
// Also pass through abs values and quadrant for Stage 5
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
sin_neg_reg <= 16'h0000;
|
sin_neg_reg <= 16'h0000;
|
||||||
cos_neg_reg <= -16'h7FFF;
|
cos_neg_reg <= -16'h7FFF;
|
||||||
sin_abs_reg2 <= 16'h0000;
|
sin_abs_reg2 <= 16'h0000;
|
||||||
@@ -318,8 +337,8 @@ end
|
|||||||
// Stage 5: Quadrant sign application → final sin/cos output
|
// Stage 5: Quadrant sign application → final sin/cos output
|
||||||
// Uses pre-computed negated values from Stage 4 — pure MUX, no arithmetic
|
// Uses pre-computed negated values from Stage 4 — pure MUX, no arithmetic
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
sin_out <= 16'h0000;
|
sin_out <= 16'h0000;
|
||||||
cos_out <= 16'h7FFF;
|
cos_out <= 16'h7FFF;
|
||||||
end else if (valid_pipe[4]) begin
|
end else if (valid_pipe[4]) begin
|
||||||
@@ -347,8 +366,8 @@ end
|
|||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Valid pipeline and dds_ready (6-stage latency)
|
// Valid pipeline and dds_ready (6-stage latency)
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
always @(posedge clk_400m or negedge reset_n) begin
|
always @(posedge clk_400m) begin
|
||||||
if (!reset_n) begin
|
if (reset_h) begin
|
||||||
valid_pipe <= 6'b000000;
|
valid_pipe <= 6'b000000;
|
||||||
dds_ready <= 1'b0;
|
dds_ready <= 1'b0;
|
||||||
end else begin
|
end else begin
|
||||||
|
|||||||
@@ -11,8 +11,10 @@ module radar_receiver_final (
|
|||||||
input wire adc_dco_n, // Data Clock Output N (400MHz LVDS)
|
input wire adc_dco_n, // Data Clock Output N (400MHz LVDS)
|
||||||
output wire adc_pwdn,
|
output wire adc_pwdn,
|
||||||
|
|
||||||
// Chirp counter from transmitter (for frame sync and matched filter)
|
// Chirp counter from transmitter (for matched filter indexing)
|
||||||
input wire [5:0] chirp_counter,
|
input wire [5:0] chirp_counter,
|
||||||
|
// Frame-start pulse from transmitter (CDC-synchronized, 1 clk_100m cycle)
|
||||||
|
input wire tx_frame_start,
|
||||||
|
|
||||||
output wire [31:0] doppler_output,
|
output wire [31:0] doppler_output,
|
||||||
output wire doppler_valid,
|
output wire doppler_valid,
|
||||||
@@ -392,32 +394,31 @@ mti_canceller #(
|
|||||||
.mti_first_chirp(mti_first_chirp)
|
.mti_first_chirp(mti_first_chirp)
|
||||||
);
|
);
|
||||||
|
|
||||||
// ========== FRAME SYNC USING chirp_counter ==========
|
// ========== FRAME SYNC FROM TRANSMITTER ==========
|
||||||
reg [5:0] chirp_counter_prev;
|
// [FPGA-001 FIXED] Use the authoritative new_chirp_frame signal from the
|
||||||
|
// transmitter (via plfm_chirp_controller_enhanced), CDC-synchronized to
|
||||||
|
// clk_100m in radar_system_top. Previous code tried to derive frame
|
||||||
|
// boundaries from chirp_counter == 0, but that counter comes from the
|
||||||
|
// transmitter path (plfm_chirp_controller_enhanced) which does NOT wrap
|
||||||
|
// at chirps_per_elev — it overflows to N and only wraps at 6-bit rollover
|
||||||
|
// (64). This caused frame pulses at half the expected rate for N=32.
|
||||||
|
reg tx_frame_start_prev;
|
||||||
reg new_frame_pulse;
|
reg new_frame_pulse;
|
||||||
|
|
||||||
always @(posedge clk or negedge reset_n) begin
|
always @(posedge clk or negedge reset_n) begin
|
||||||
if (!reset_n) begin
|
if (!reset_n) begin
|
||||||
chirp_counter_prev <= 6'd0;
|
tx_frame_start_prev <= 1'b0;
|
||||||
new_frame_pulse <= 1'b0;
|
new_frame_pulse <= 1'b0;
|
||||||
end else begin
|
end else begin
|
||||||
// Default: no pulse
|
|
||||||
new_frame_pulse <= 1'b0;
|
new_frame_pulse <= 1'b0;
|
||||||
|
|
||||||
// Dynamic frame detection using host_chirps_per_elev.
|
// Edge detect: tx_frame_start is a toggle-CDC derived pulse that
|
||||||
// Detect frame boundary when chirp_counter changes AND is a
|
// may be 1 clock wide. Capture rising edge for clean 1-cycle pulse.
|
||||||
// multiple of host_chirps_per_elev (0, N, 2N, 3N, ...).
|
if (tx_frame_start && !tx_frame_start_prev) begin
|
||||||
// Uses a modulo counter that resets at host_chirps_per_elev.
|
new_frame_pulse <= 1'b1;
|
||||||
if (chirp_counter != chirp_counter_prev) begin
|
|
||||||
if (chirp_counter == 6'd0 ||
|
|
||||||
chirp_counter == host_chirps_per_elev ||
|
|
||||||
chirp_counter == {host_chirps_per_elev, 1'b0}) begin
|
|
||||||
new_frame_pulse <= 1'b1;
|
|
||||||
end
|
|
||||||
end
|
end
|
||||||
|
|
||||||
// Store previous value
|
tx_frame_start_prev <= tx_frame_start;
|
||||||
chirp_counter_prev <= chirp_counter;
|
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -483,14 +484,6 @@ always @(posedge clk or negedge reset_n) begin
|
|||||||
`endif
|
`endif
|
||||||
chirps_in_current_frame <= 0;
|
chirps_in_current_frame <= 0;
|
||||||
end
|
end
|
||||||
|
|
||||||
// Monitor chirp counter pattern
|
|
||||||
if (chirp_counter != chirp_counter_prev) begin
|
|
||||||
`ifdef SIMULATION
|
|
||||||
$display("[TOP] chirp_counter: %0d ? %0d",
|
|
||||||
chirp_counter_prev, chirp_counter);
|
|
||||||
`endif
|
|
||||||
end
|
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|||||||
@@ -130,7 +130,7 @@ module radar_system_top (
|
|||||||
// FPGA→STM32 GPIO outputs (DIG_5..DIG_7 on 50T board)
|
// FPGA→STM32 GPIO outputs (DIG_5..DIG_7 on 50T board)
|
||||||
// Used by STM32 outer AGC loop to read saturation state without USB polling.
|
// Used by STM32 outer AGC loop to read saturation state without USB polling.
|
||||||
output wire gpio_dig5, // DIG_5 (H11→PD13): AGC saturation flag (1=clipping detected)
|
output wire gpio_dig5, // DIG_5 (H11→PD13): AGC saturation flag (1=clipping detected)
|
||||||
output wire gpio_dig6, // DIG_6 (G12→PD14): reserved (tied low)
|
output wire gpio_dig6, // DIG_6 (G12→PD14): AGC enable flag (mirrors host_agc_enable)
|
||||||
output wire gpio_dig7 // DIG_7 (H12→PD15): reserved (tied low)
|
output wire gpio_dig7 // DIG_7 (H12→PD15): reserved (tied low)
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -142,7 +142,7 @@ module radar_system_top (
|
|||||||
parameter USE_LONG_CHIRP = 1'b1; // Default to long chirp
|
parameter USE_LONG_CHIRP = 1'b1; // Default to long chirp
|
||||||
parameter DOPPLER_ENABLE = 1'b1; // Enable Doppler processing
|
parameter DOPPLER_ENABLE = 1'b1; // Enable Doppler processing
|
||||||
parameter USB_ENABLE = 1'b1; // Enable USB data transfer
|
parameter USB_ENABLE = 1'b1; // Enable USB data transfer
|
||||||
parameter USB_MODE = 0; // 0=FT601 (32-bit, 200T), 1=FT2232H (8-bit, 50T)
|
parameter USB_MODE = 1; // 0=FT601 (32-bit, 200T), 1=FT2232H (8-bit, 50T) — default: FT2232H production board
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// INTERNAL SIGNALS
|
// INTERNAL SIGNALS
|
||||||
@@ -243,12 +243,12 @@ reg [5:0] host_chirps_per_elev; // Opcode 0x15 (default 32)
|
|||||||
reg host_status_request; // Opcode 0xFF (self-clearing pulse)
|
reg host_status_request; // Opcode 0xFF (self-clearing pulse)
|
||||||
|
|
||||||
// Fix 4: Doppler/chirps mismatch protection
|
// Fix 4: Doppler/chirps mismatch protection
|
||||||
// DOPPLER_FRAME_CHIRPS is the fixed chirp count expected by the staggered-PRI
|
// DOPPLER_FRAME_CHIRPS is the fixed chirp count expected by the staggered-PRI
|
||||||
// Doppler path (16 long + 16 short). If host sets chirps_per_elev to a
|
// Doppler path (16 long + 16 short). If host sets chirps_per_elev to a
|
||||||
// different value, Doppler accumulation is corrupted. Clamp at command decode
|
// different value, Doppler accumulation is corrupted. Clamp at command decode
|
||||||
// and flag the mismatch so the host knows.
|
// and flag the mismatch so the host knows.
|
||||||
localparam DOPPLER_FRAME_CHIRPS = 32; // Total chirps per Doppler frame
|
localparam DOPPLER_FRAME_CHIRPS = 32; // Total chirps per Doppler frame
|
||||||
reg chirps_mismatch_error; // Set if host tried to set chirps != FFT size
|
reg chirps_mismatch_error; // Set if host tried to set chirps != FFT size
|
||||||
|
|
||||||
// Fix 7: Range-mode register (opcode 0x20)
|
// Fix 7: Range-mode register (opcode 0x20)
|
||||||
// Future-proofing for 3km/10km antenna switching.
|
// Future-proofing for 3km/10km antenna switching.
|
||||||
@@ -505,6 +505,8 @@ radar_receiver_final rx_inst (
|
|||||||
|
|
||||||
// Chirp counter from transmitter (CDC-synchronized from 120 MHz domain)
|
// Chirp counter from transmitter (CDC-synchronized from 120 MHz domain)
|
||||||
.chirp_counter(tx_current_chirp_sync),
|
.chirp_counter(tx_current_chirp_sync),
|
||||||
|
// Frame-start pulse from transmitter (CDC-synchronized toggle→pulse)
|
||||||
|
.tx_frame_start(tx_new_chirp_frame_sync),
|
||||||
|
|
||||||
// ADC Physical Interface
|
// ADC Physical Interface
|
||||||
.adc_d_p(adc_d_p),
|
.adc_d_p(adc_d_p),
|
||||||
@@ -576,21 +578,21 @@ assign rx_doppler_data_valid = rx_doppler_valid;
|
|||||||
// ============================================================================
|
// ============================================================================
|
||||||
// DC NOTCH FILTER (post-Doppler-FFT, pre-CFAR)
|
// DC NOTCH FILTER (post-Doppler-FFT, pre-CFAR)
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
// Zeros out Doppler bins within ±host_dc_notch_width of DC for BOTH
|
// Zeros out Doppler bins within ±host_dc_notch_width of DC for BOTH
|
||||||
// sub-frames in the dual 16-pt FFT architecture.
|
// sub-frames in the dual 16-pt FFT architecture.
|
||||||
// doppler_bin[4:0] = {sub_frame, bin[3:0]}:
|
// doppler_bin[4:0] = {sub_frame, bin[3:0]}:
|
||||||
// Sub-frame 0: bins 0-15, DC = bin 0, wrap = bin 15
|
// Sub-frame 0: bins 0-15, DC = bin 0, wrap = bin 15
|
||||||
// Sub-frame 1: bins 16-31, DC = bin 16, wrap = bin 31
|
// Sub-frame 1: bins 16-31, DC = bin 16, wrap = bin 31
|
||||||
// notch_width=1 → zero bins {0,16}. notch_width=2 → zero bins
|
// notch_width=1 → zero bins {0,16}. notch_width=2 → zero bins
|
||||||
// {0,1,15,16,17,31}. etc.
|
// {0,1,15,16,17,31}. etc.
|
||||||
// When host_dc_notch_width=0: pass-through (no zeroing).
|
// When host_dc_notch_width=0: pass-through (no zeroing).
|
||||||
|
|
||||||
wire dc_notch_active;
|
wire dc_notch_active;
|
||||||
wire [4:0] dop_bin_unsigned = rx_doppler_bin;
|
wire [4:0] dop_bin_unsigned = rx_doppler_bin;
|
||||||
wire [3:0] bin_within_sf = dop_bin_unsigned[3:0];
|
wire [3:0] bin_within_sf = dop_bin_unsigned[3:0];
|
||||||
assign dc_notch_active = (host_dc_notch_width != 3'd0) &&
|
assign dc_notch_active = (host_dc_notch_width != 3'd0) &&
|
||||||
(bin_within_sf < {1'b0, host_dc_notch_width} ||
|
(bin_within_sf < {1'b0, host_dc_notch_width} ||
|
||||||
bin_within_sf > (4'd15 - {1'b0, host_dc_notch_width} + 4'd1));
|
bin_within_sf > (4'd15 - {1'b0, host_dc_notch_width} + 4'd1));
|
||||||
|
|
||||||
// Notched Doppler data: zero I/Q when in notch zone, pass through otherwise
|
// Notched Doppler data: zero I/Q when in notch zone, pass through otherwise
|
||||||
wire [31:0] notched_doppler_data = dc_notch_active ? 32'd0 : rx_doppler_output;
|
wire [31:0] notched_doppler_data = dc_notch_active ? 32'd0 : rx_doppler_output;
|
||||||
@@ -957,19 +959,19 @@ always @(posedge clk_100m_buf or negedge sys_reset_n) begin
|
|||||||
8'h13: host_short_chirp_cycles <= usb_cmd_value;
|
8'h13: host_short_chirp_cycles <= usb_cmd_value;
|
||||||
8'h14: host_short_listen_cycles <= usb_cmd_value;
|
8'h14: host_short_listen_cycles <= usb_cmd_value;
|
||||||
8'h15: begin
|
8'h15: begin
|
||||||
// Fix 4: Clamp chirps_per_elev to the fixed Doppler frame size.
|
// Fix 4: Clamp chirps_per_elev to the fixed Doppler frame size.
|
||||||
// If host requests a different value, clamp and set error flag.
|
// If host requests a different value, clamp and set error flag.
|
||||||
if (usb_cmd_value[5:0] > DOPPLER_FRAME_CHIRPS[5:0]) begin
|
if (usb_cmd_value[5:0] > DOPPLER_FRAME_CHIRPS[5:0]) begin
|
||||||
host_chirps_per_elev <= DOPPLER_FRAME_CHIRPS[5:0];
|
host_chirps_per_elev <= DOPPLER_FRAME_CHIRPS[5:0];
|
||||||
chirps_mismatch_error <= 1'b1;
|
chirps_mismatch_error <= 1'b1;
|
||||||
end else if (usb_cmd_value[5:0] == 6'd0) begin
|
end else if (usb_cmd_value[5:0] == 6'd0) begin
|
||||||
host_chirps_per_elev <= DOPPLER_FRAME_CHIRPS[5:0];
|
host_chirps_per_elev <= DOPPLER_FRAME_CHIRPS[5:0];
|
||||||
chirps_mismatch_error <= 1'b1;
|
chirps_mismatch_error <= 1'b1;
|
||||||
end else begin
|
end else begin
|
||||||
host_chirps_per_elev <= usb_cmd_value[5:0];
|
host_chirps_per_elev <= usb_cmd_value[5:0];
|
||||||
// Clear error only if value matches FFT size exactly
|
// Clear error only if value matches FFT size exactly
|
||||||
chirps_mismatch_error <= (usb_cmd_value[5:0] != DOPPLER_FRAME_CHIRPS[5:0]);
|
chirps_mismatch_error <= (usb_cmd_value[5:0] != DOPPLER_FRAME_CHIRPS[5:0]);
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
8'h16: host_gain_shift <= usb_cmd_value[3:0]; // Fix 3: digital gain
|
8'h16: host_gain_shift <= usb_cmd_value[3:0]; // Fix 3: digital gain
|
||||||
8'h20: host_range_mode <= usb_cmd_value[1:0]; // Fix 7: range mode
|
8'h20: host_range_mode <= usb_cmd_value[1:0]; // Fix 7: range mode
|
||||||
@@ -1035,9 +1037,11 @@ assign system_status = status_reg;
|
|||||||
// ============================================================================
|
// ============================================================================
|
||||||
// DIG_5: AGC saturation flag — high when per-frame saturation_count > 0.
|
// DIG_5: AGC saturation flag — high when per-frame saturation_count > 0.
|
||||||
// STM32 reads PD13 to detect clipping and adjust ADAR1000 VGA gain.
|
// STM32 reads PD13 to detect clipping and adjust ADAR1000 VGA gain.
|
||||||
// DIG_6, DIG_7: Reserved (tied low for future use).
|
// DIG_6: AGC enable flag — mirrors host_agc_enable so STM32 outer-loop AGC
|
||||||
|
// tracks the FPGA register as single source of truth.
|
||||||
|
// DIG_7: Reserved (tied low for future use).
|
||||||
assign gpio_dig5 = (rx_agc_saturation_count != 8'd0);
|
assign gpio_dig5 = (rx_agc_saturation_count != 8'd0);
|
||||||
assign gpio_dig6 = 1'b0;
|
assign gpio_dig6 = host_agc_enable;
|
||||||
assign gpio_dig7 = 1'b0;
|
assign gpio_dig7 = 1'b0;
|
||||||
|
|
||||||
// ============================================================================
|
// ============================================================================
|
||||||
@@ -1071,4 +1075,4 @@ always @(posedge clk_100m_buf) begin
|
|||||||
end
|
end
|
||||||
`endif
|
`endif
|
||||||
|
|
||||||
endmodule
|
endmodule
|
||||||
|
|||||||
@@ -70,6 +70,7 @@ PROD_RTL=(
|
|||||||
xfft_16.v
|
xfft_16.v
|
||||||
fft_engine.v
|
fft_engine.v
|
||||||
usb_data_interface.v
|
usb_data_interface.v
|
||||||
|
usb_data_interface_ft2232h.v
|
||||||
edge_detector.v
|
edge_detector.v
|
||||||
radar_mode_controller.v
|
radar_mode_controller.v
|
||||||
rx_gain_control.v
|
rx_gain_control.v
|
||||||
@@ -452,7 +453,8 @@ if [[ "$QUICK" -eq 0 ]]; then
|
|||||||
chirp_memory_loader_param.v latency_buffer.v \
|
chirp_memory_loader_param.v latency_buffer.v \
|
||||||
matched_filter_multi_segment.v matched_filter_processing_chain.v \
|
matched_filter_multi_segment.v matched_filter_processing_chain.v \
|
||||||
range_bin_decimator.v doppler_processor.v xfft_16.v fft_engine.v \
|
range_bin_decimator.v doppler_processor.v xfft_16.v fft_engine.v \
|
||||||
usb_data_interface.v edge_detector.v radar_mode_controller.v \
|
usb_data_interface.v usb_data_interface_ft2232h.v \
|
||||||
|
edge_detector.v radar_mode_controller.v \
|
||||||
rx_gain_control.v cfar_ca.v mti_canceller.v fpga_self_test.v
|
rx_gain_control.v cfar_ca.v mti_canceller.v fpga_self_test.v
|
||||||
|
|
||||||
# E2E integration (46 strict checks: TX, RX, USB R/W, CDC, safety, reset)
|
# E2E integration (46 strict checks: TX, RX, USB R/W, CDC, safety, reset)
|
||||||
@@ -466,7 +468,8 @@ if [[ "$QUICK" -eq 0 ]]; then
|
|||||||
chirp_memory_loader_param.v latency_buffer.v \
|
chirp_memory_loader_param.v latency_buffer.v \
|
||||||
matched_filter_multi_segment.v matched_filter_processing_chain.v \
|
matched_filter_multi_segment.v matched_filter_processing_chain.v \
|
||||||
range_bin_decimator.v doppler_processor.v xfft_16.v fft_engine.v \
|
range_bin_decimator.v doppler_processor.v xfft_16.v fft_engine.v \
|
||||||
usb_data_interface.v edge_detector.v radar_mode_controller.v \
|
usb_data_interface.v usb_data_interface_ft2232h.v \
|
||||||
|
edge_detector.v radar_mode_controller.v \
|
||||||
rx_gain_control.v cfar_ca.v mti_canceller.v fpga_self_test.v
|
rx_gain_control.v cfar_ca.v mti_canceller.v fpga_self_test.v
|
||||||
else
|
else
|
||||||
echo " (skipped receiver golden + system top + E2E — use without --quick)"
|
echo " (skipped receiver golden + system top + E2E — use without --quick)"
|
||||||
|
|||||||
@@ -291,9 +291,12 @@ class Mixer:
|
|||||||
Convert 8-bit unsigned ADC to 18-bit signed.
|
Convert 8-bit unsigned ADC to 18-bit signed.
|
||||||
RTL: adc_signed_w = {1'b0, adc_data, {9{1'b0}}} -
|
RTL: adc_signed_w = {1'b0, adc_data, {9{1'b0}}} -
|
||||||
{1'b0, {8{1'b1}}, {9{1'b0}}} / 2
|
{1'b0, {8{1'b1}}, {9{1'b0}}} / 2
|
||||||
= (adc_data << 9) - (0xFF << 9) / 2
|
|
||||||
= (adc_data << 9) - (0xFF << 8) [integer division]
|
Verilog '/' binds tighter than '-', so the division applies
|
||||||
= (adc_data << 9) - 0x7F80
|
only to the second concatenation:
|
||||||
|
{1'b0, 8'hFF, 9'b0} = 0x1FE00
|
||||||
|
0x1FE00 / 2 = 0xFF00 = 65280
|
||||||
|
Result: (adc_data << 9) - 0xFF00
|
||||||
"""
|
"""
|
||||||
adc_data_8bit = adc_data_8bit & 0xFF
|
adc_data_8bit = adc_data_8bit & 0xFF
|
||||||
# {1'b0, adc_data, 9'b0} = adc_data << 9, zero-padded to 18 bits
|
# {1'b0, adc_data, 9'b0} = adc_data << 9, zero-padded to 18 bits
|
||||||
|
|||||||
@@ -290,9 +290,9 @@ def run_ddc(adc_samples):
|
|||||||
for n in range(n_samples):
|
for n in range(n_samples):
|
||||||
# ADC sign conversion: RTL does offset binary → signed 18-bit
|
# ADC sign conversion: RTL does offset binary → signed 18-bit
|
||||||
# adc_signed_w = {1'b0, adc_data, 9'b0} - {1'b0, 8'hFF, 9'b0}/2
|
# adc_signed_w = {1'b0, adc_data, 9'b0} - {1'b0, 8'hFF, 9'b0}/2
|
||||||
# Simplified: center around zero, scale to 18-bit
|
# Exact: (adc_val << 9) - 0xFF00, where 0xFF00 = {1'b0,8'hFF,9'b0}/2
|
||||||
adc_val = int(adc_samples[n])
|
adc_val = int(adc_samples[n])
|
||||||
adc_signed = (adc_val - 128) << 9 # Approximate RTL sign conversion to 18-bit
|
adc_signed = (adc_val << 9) - 0xFF00 # Exact RTL: {1'b0,adc,9'b0} - {1'b0,8'hFF,9'b0}/2
|
||||||
adc_signed = saturate(adc_signed, 18)
|
adc_signed = saturate(adc_signed, 18)
|
||||||
|
|
||||||
# NCO lookup (ignoring dithering for golden reference)
|
# NCO lookup (ignoring dithering for golden reference)
|
||||||
|
|||||||
+2455
-2455
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -619,7 +619,7 @@ initial begin
|
|||||||
// Optional: dump specific signals for debugging
|
// Optional: dump specific signals for debugging
|
||||||
$dumpvars(1, dut.tx_inst);
|
$dumpvars(1, dut.tx_inst);
|
||||||
$dumpvars(1, dut.rx_inst);
|
$dumpvars(1, dut.rx_inst);
|
||||||
$dumpvars(1, dut.gen_ft601.usb_inst);
|
$dumpvars(1, dut.gen_ft2232h.usb_inst);
|
||||||
end
|
end
|
||||||
|
|
||||||
endmodule
|
endmodule
|
||||||
|
|||||||
@@ -96,15 +96,31 @@ end
|
|||||||
reg [5:0] chirp_counter;
|
reg [5:0] chirp_counter;
|
||||||
reg mc_new_chirp_prev;
|
reg mc_new_chirp_prev;
|
||||||
|
|
||||||
|
// Frame-start pulse: mirrors the real transmitter's new_chirp_frame signal.
|
||||||
|
// In the real system this fires on IDLE→LONG_CHIRP transitions in the chirp
|
||||||
|
// controller. Here we derive it from the mode controller's chirp_count
|
||||||
|
// wrapping back to 0 (which wraps correctly at cfg_chirps_per_elev).
|
||||||
|
reg tx_frame_start;
|
||||||
|
reg [5:0] rmc_chirp_prev;
|
||||||
|
|
||||||
always @(posedge clk_100m or negedge reset_n) begin
|
always @(posedge clk_100m or negedge reset_n) begin
|
||||||
if (!reset_n) begin
|
if (!reset_n) begin
|
||||||
chirp_counter <= 6'd0;
|
chirp_counter <= 6'd0;
|
||||||
mc_new_chirp_prev <= 1'b0;
|
mc_new_chirp_prev <= 1'b0;
|
||||||
|
tx_frame_start <= 1'b0;
|
||||||
|
rmc_chirp_prev <= 6'd0;
|
||||||
end else begin
|
end else begin
|
||||||
mc_new_chirp_prev <= dut.mc_new_chirp;
|
mc_new_chirp_prev <= dut.mc_new_chirp;
|
||||||
if (dut.mc_new_chirp != mc_new_chirp_prev) begin
|
if (dut.mc_new_chirp != mc_new_chirp_prev) begin
|
||||||
chirp_counter <= chirp_counter + 1;
|
chirp_counter <= chirp_counter + 1;
|
||||||
end
|
end
|
||||||
|
|
||||||
|
// Detect when the internal mode controller's chirp_count wraps to 0
|
||||||
|
tx_frame_start <= 1'b0;
|
||||||
|
if (dut.rmc_chirp_count == 6'd0 && rmc_chirp_prev != 6'd0) begin
|
||||||
|
tx_frame_start <= 1'b1;
|
||||||
|
end
|
||||||
|
rmc_chirp_prev <= dut.rmc_chirp_count;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -128,6 +144,7 @@ radar_receiver_final dut (
|
|||||||
.adc_pwdn(),
|
.adc_pwdn(),
|
||||||
|
|
||||||
.chirp_counter(chirp_counter),
|
.chirp_counter(chirp_counter),
|
||||||
|
.tx_frame_start(tx_frame_start),
|
||||||
|
|
||||||
.doppler_output(doppler_output),
|
.doppler_output(doppler_output),
|
||||||
.doppler_valid(doppler_valid),
|
.doppler_valid(doppler_valid),
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
#!/usr/bin/env python3
|
#!/usr/bin/env python3
|
||||||
"""
|
"""
|
||||||
AERIS-10 Radar Dashboard
|
AERIS-10 Radar Dashboard (Tkinter)
|
||||||
===================================================
|
===================================================
|
||||||
Real-time visualization and control for the AERIS-10 phased-array radar
|
Real-time visualization and control for the AERIS-10 phased-array radar
|
||||||
via FT2232H USB 2.0 interface.
|
via FT2232H USB 2.0 interface.
|
||||||
@@ -14,36 +14,52 @@ Features:
|
|||||||
0x01-0x04, 0x10-0x16, 0x20-0x27, 0x30-0x31, 0xFF)
|
0x01-0x04, 0x10-0x16, 0x20-0x27, 0x30-0x31, 0xFF)
|
||||||
- Configuration panel for all radar parameters
|
- Configuration panel for all radar parameters
|
||||||
- HDF5 data recording for offline analysis
|
- HDF5 data recording for offline analysis
|
||||||
|
- Replay mode (co-sim dirs, raw IQ .npy, HDF5) with transport controls
|
||||||
|
- Demo mode with synthetic moving targets
|
||||||
|
- Detected targets table
|
||||||
|
- Dual dispatch: FPGA controls route to SoftwareFPGA during replay
|
||||||
- Mock mode for development/testing without hardware
|
- Mock mode for development/testing without hardware
|
||||||
|
|
||||||
Usage:
|
Usage:
|
||||||
python radar_dashboard.py # Launch with mock data
|
python GUI_V65_Tk.py # Launch with mock data
|
||||||
python radar_dashboard.py --live # Launch with FT2232H hardware
|
python GUI_V65_Tk.py --live # Launch with FT2232H hardware
|
||||||
python radar_dashboard.py --record # Launch with HDF5 recording
|
python GUI_V65_Tk.py --record # Launch with HDF5 recording
|
||||||
|
python GUI_V65_Tk.py --replay path/to/data # Auto-load replay
|
||||||
|
python GUI_V65_Tk.py --demo # Start in demo mode
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import os
|
import os
|
||||||
|
import math
|
||||||
import time
|
import time
|
||||||
|
import copy
|
||||||
import queue
|
import queue
|
||||||
|
import random
|
||||||
import logging
|
import logging
|
||||||
import argparse
|
import argparse
|
||||||
import threading
|
import threading
|
||||||
import contextlib
|
import contextlib
|
||||||
from collections import deque
|
from collections import deque
|
||||||
|
from pathlib import Path
|
||||||
|
from typing import ClassVar
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|
||||||
import tkinter as tk
|
try:
|
||||||
from tkinter import ttk, filedialog
|
import tkinter as tk
|
||||||
|
from tkinter import ttk, filedialog
|
||||||
|
|
||||||
import matplotlib
|
import matplotlib
|
||||||
matplotlib.use("TkAgg")
|
matplotlib.use("TkAgg")
|
||||||
from matplotlib.figure import Figure
|
from matplotlib.figure import Figure
|
||||||
from matplotlib.backends.backend_tkagg import FigureCanvasTkAgg
|
from matplotlib.backends.backend_tkagg import FigureCanvasTkAgg
|
||||||
|
|
||||||
|
_HAS_GUI = True
|
||||||
|
except (ModuleNotFoundError, ImportError):
|
||||||
|
_HAS_GUI = False
|
||||||
|
|
||||||
# Import protocol layer (no GUI deps)
|
# Import protocol layer (no GUI deps)
|
||||||
from radar_protocol import (
|
from radar_protocol import (
|
||||||
RadarProtocol, FT2232HConnection, ReplayConnection,
|
RadarProtocol, FT2232HConnection,
|
||||||
DataRecorder, RadarAcquisition,
|
DataRecorder, RadarAcquisition,
|
||||||
RadarFrame, StatusResponse,
|
RadarFrame, StatusResponse,
|
||||||
NUM_RANGE_BINS, NUM_DOPPLER_BINS, WATERFALL_DEPTH,
|
NUM_RANGE_BINS, NUM_DOPPLER_BINS, WATERFALL_DEPTH,
|
||||||
@@ -54,7 +70,7 @@ logging.basicConfig(
|
|||||||
format="%(asctime)s [%(levelname)s] %(message)s",
|
format="%(asctime)s [%(levelname)s] %(message)s",
|
||||||
datefmt="%H:%M:%S",
|
datefmt="%H:%M:%S",
|
||||||
)
|
)
|
||||||
log = logging.getLogger("radar_dashboard")
|
log = logging.getLogger("GUI_V65_Tk")
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@@ -73,6 +89,296 @@ YELLOW = "#f9e2af"
|
|||||||
SURFACE = "#313244"
|
SURFACE = "#313244"
|
||||||
|
|
||||||
|
|
||||||
|
# ============================================================================
|
||||||
|
# Demo Target Simulator (Tkinter timer-based)
|
||||||
|
# ============================================================================
|
||||||
|
|
||||||
|
class DemoTarget:
|
||||||
|
"""Single simulated target with kinematics."""
|
||||||
|
|
||||||
|
__slots__ = ("azimuth", "classification", "id", "range_m", "snr", "velocity")
|
||||||
|
|
||||||
|
# Physical range grid: 64 bins x ~4.8 m/bin = ~307 m max
|
||||||
|
_RANGE_PER_BIN: float = (3e8 / (2 * 500e6)) * 16 # ~4.8 m
|
||||||
|
_MAX_RANGE: float = _RANGE_PER_BIN * NUM_RANGE_BINS # ~307 m
|
||||||
|
|
||||||
|
def __init__(self, tid: int):
|
||||||
|
self.id = tid
|
||||||
|
self.range_m = random.uniform(20, self._MAX_RANGE - 20)
|
||||||
|
self.velocity = random.uniform(-10, 10)
|
||||||
|
self.azimuth = random.uniform(0, 360)
|
||||||
|
self.snr = random.uniform(10, 35)
|
||||||
|
self.classification = random.choice(
|
||||||
|
["aircraft", "drone", "bird", "unknown"])
|
||||||
|
|
||||||
|
def step(self) -> bool:
|
||||||
|
"""Advance one tick. Return False if target exits coverage."""
|
||||||
|
self.range_m -= self.velocity * 0.1
|
||||||
|
if self.range_m < 5 or self.range_m > self._MAX_RANGE:
|
||||||
|
return False
|
||||||
|
self.velocity = max(-20, min(20, self.velocity + random.uniform(-1, 1)))
|
||||||
|
self.azimuth = (self.azimuth + random.uniform(-0.5, 0.5)) % 360
|
||||||
|
self.snr = max(0, min(50, self.snr + random.uniform(-1, 1)))
|
||||||
|
return True
|
||||||
|
|
||||||
|
|
||||||
|
class DemoSimulator:
|
||||||
|
"""Timer-driven demo target generator for the Tkinter dashboard.
|
||||||
|
|
||||||
|
Produces synthetic ``RadarFrame`` objects and a target list each tick,
|
||||||
|
pushing them into the dashboard's ``frame_queue`` and ``_ui_queue``.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(self, frame_queue: queue.Queue, ui_queue: queue.Queue,
|
||||||
|
root: tk.Tk, interval_ms: int = 500):
|
||||||
|
self._frame_queue = frame_queue
|
||||||
|
self._ui_queue = ui_queue
|
||||||
|
self._root = root
|
||||||
|
self._interval_ms = interval_ms
|
||||||
|
self._targets: list[DemoTarget] = []
|
||||||
|
self._next_id = 1
|
||||||
|
self._frame_number = 0
|
||||||
|
self._after_id: str | None = None
|
||||||
|
|
||||||
|
# Seed initial targets
|
||||||
|
for _ in range(8):
|
||||||
|
self._add_target()
|
||||||
|
|
||||||
|
def start(self):
|
||||||
|
self._tick()
|
||||||
|
|
||||||
|
def stop(self):
|
||||||
|
if self._after_id is not None:
|
||||||
|
self._root.after_cancel(self._after_id)
|
||||||
|
self._after_id = None
|
||||||
|
|
||||||
|
def add_random_target(self):
|
||||||
|
self._add_target()
|
||||||
|
|
||||||
|
def _add_target(self):
|
||||||
|
t = DemoTarget(self._next_id)
|
||||||
|
self._next_id += 1
|
||||||
|
self._targets.append(t)
|
||||||
|
|
||||||
|
def _tick(self):
|
||||||
|
updated: list[DemoTarget] = [t for t in self._targets if t.step()]
|
||||||
|
if len(updated) < 5 or (random.random() < 0.05 and len(updated) < 15):
|
||||||
|
self._add_target()
|
||||||
|
updated.append(self._targets[-1])
|
||||||
|
self._targets = updated
|
||||||
|
|
||||||
|
# Synthesize a RadarFrame with Gaussian blobs for each target
|
||||||
|
frame = self._make_frame(updated)
|
||||||
|
with contextlib.suppress(queue.Full):
|
||||||
|
self._frame_queue.put_nowait(frame)
|
||||||
|
|
||||||
|
# Post target info for the detected-targets treeview
|
||||||
|
target_dicts = [
|
||||||
|
{"id": t.id, "range_m": t.range_m, "velocity": t.velocity,
|
||||||
|
"azimuth": t.azimuth, "snr": t.snr, "class": t.classification}
|
||||||
|
for t in updated
|
||||||
|
]
|
||||||
|
self._ui_queue.put(("demo_targets", target_dicts))
|
||||||
|
|
||||||
|
self._after_id = self._root.after(self._interval_ms, self._tick)
|
||||||
|
|
||||||
|
def _make_frame(self, targets: list[DemoTarget]) -> RadarFrame:
|
||||||
|
"""Build a synthetic RadarFrame from target list."""
|
||||||
|
mag = np.zeros((NUM_RANGE_BINS, NUM_DOPPLER_BINS), dtype=np.float64)
|
||||||
|
det = np.zeros((NUM_RANGE_BINS, NUM_DOPPLER_BINS), dtype=np.uint8)
|
||||||
|
|
||||||
|
# Range/Doppler scaling (approximate)
|
||||||
|
range_per_bin = (3e8 / (2 * 500e6)) * 16 # ~4.8 m/bin
|
||||||
|
max_range = range_per_bin * NUM_RANGE_BINS
|
||||||
|
vel_per_bin = 1.484 # m/s per Doppler bin (from WaveformConfig)
|
||||||
|
|
||||||
|
for t in targets:
|
||||||
|
if t.range_m > max_range or t.range_m < 0:
|
||||||
|
continue
|
||||||
|
r_bin = int(t.range_m / range_per_bin)
|
||||||
|
d_bin = int((t.velocity / vel_per_bin) + NUM_DOPPLER_BINS / 2)
|
||||||
|
r_bin = max(0, min(NUM_RANGE_BINS - 1, r_bin))
|
||||||
|
d_bin = max(0, min(NUM_DOPPLER_BINS - 1, d_bin))
|
||||||
|
|
||||||
|
# Gaussian-ish blob
|
||||||
|
amplitude = 500 + t.snr * 200
|
||||||
|
for dr in range(-2, 3):
|
||||||
|
for dd in range(-1, 2):
|
||||||
|
ri = r_bin + dr
|
||||||
|
di = d_bin + dd
|
||||||
|
if 0 <= ri < NUM_RANGE_BINS and 0 <= di < NUM_DOPPLER_BINS:
|
||||||
|
w = math.exp(-0.5 * (dr**2 + dd**2))
|
||||||
|
mag[ri, di] += amplitude * w
|
||||||
|
if w > 0.5:
|
||||||
|
det[ri, di] = 1
|
||||||
|
|
||||||
|
rd_i = (mag * 0.5).astype(np.int16)
|
||||||
|
rd_q = np.zeros_like(rd_i)
|
||||||
|
rp = mag.max(axis=1)
|
||||||
|
|
||||||
|
self._frame_number += 1
|
||||||
|
return RadarFrame(
|
||||||
|
timestamp=time.time(),
|
||||||
|
range_doppler_i=rd_i,
|
||||||
|
range_doppler_q=rd_q,
|
||||||
|
magnitude=mag,
|
||||||
|
detections=det,
|
||||||
|
range_profile=rp,
|
||||||
|
detection_count=int(det.sum()),
|
||||||
|
frame_number=self._frame_number,
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
# ============================================================================
|
||||||
|
# Replay Controller (threading-based, reuses v7.ReplayEngine)
|
||||||
|
# ============================================================================
|
||||||
|
|
||||||
|
class _ReplayController:
|
||||||
|
"""Manages replay playback in a background thread for the Tkinter dashboard.
|
||||||
|
|
||||||
|
Imports ``ReplayEngine`` and ``SoftwareFPGA`` from ``v7`` lazily so
|
||||||
|
they are only required when replay is actually used.
|
||||||
|
"""
|
||||||
|
|
||||||
|
# Speed multiplier → frame interval in seconds
|
||||||
|
SPEED_MAP: ClassVar[dict[str, float]] = {
|
||||||
|
"0.25x": 0.400,
|
||||||
|
"0.5x": 0.200,
|
||||||
|
"1x": 0.100,
|
||||||
|
"2x": 0.050,
|
||||||
|
"5x": 0.020,
|
||||||
|
"10x": 0.010,
|
||||||
|
}
|
||||||
|
|
||||||
|
def __init__(self, frame_queue: queue.Queue, ui_queue: queue.Queue):
|
||||||
|
self._frame_queue = frame_queue
|
||||||
|
self._ui_queue = ui_queue
|
||||||
|
self._engine = None # lazy
|
||||||
|
self._software_fpga = None # lazy
|
||||||
|
self._thread: threading.Thread | None = None
|
||||||
|
self._play_event = threading.Event()
|
||||||
|
self._stop_event = threading.Event()
|
||||||
|
self._lock = threading.Lock()
|
||||||
|
self._current_index = 0
|
||||||
|
self._last_emitted_index = -1
|
||||||
|
self._loop = False
|
||||||
|
self._frame_interval = 0.100 # 1x speed
|
||||||
|
|
||||||
|
def load(self, path: str) -> int:
|
||||||
|
"""Load replay data from path. Returns total frames or raises."""
|
||||||
|
from v7.replay import ReplayEngine, ReplayFormat, detect_format
|
||||||
|
from v7.software_fpga import SoftwareFPGA
|
||||||
|
|
||||||
|
fmt = detect_format(path)
|
||||||
|
if fmt == ReplayFormat.RAW_IQ_NPY:
|
||||||
|
self._software_fpga = SoftwareFPGA()
|
||||||
|
self._engine = ReplayEngine(path, software_fpga=self._software_fpga)
|
||||||
|
else:
|
||||||
|
self._engine = ReplayEngine(path)
|
||||||
|
|
||||||
|
self._current_index = 0
|
||||||
|
self._last_emitted_index = -1
|
||||||
|
self._stop_event.clear()
|
||||||
|
self._play_event.clear()
|
||||||
|
return self._engine.total_frames
|
||||||
|
|
||||||
|
@property
|
||||||
|
def total_frames(self) -> int:
|
||||||
|
return self._engine.total_frames if self._engine else 0
|
||||||
|
|
||||||
|
@property
|
||||||
|
def current_index(self) -> int:
|
||||||
|
return self._last_emitted_index if self._last_emitted_index >= 0 else 0
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_playing(self) -> bool:
|
||||||
|
return self._play_event.is_set()
|
||||||
|
|
||||||
|
@property
|
||||||
|
def software_fpga(self):
|
||||||
|
return self._software_fpga
|
||||||
|
|
||||||
|
def set_speed(self, label: str):
|
||||||
|
self._frame_interval = self.SPEED_MAP.get(label, 0.100)
|
||||||
|
|
||||||
|
def set_loop(self, loop: bool):
|
||||||
|
self._loop = loop
|
||||||
|
|
||||||
|
def play(self):
|
||||||
|
self._play_event.set()
|
||||||
|
with self._lock:
|
||||||
|
if self._current_index >= self.total_frames:
|
||||||
|
self._current_index = 0
|
||||||
|
self._ui_queue.put(("replay_state", "playing"))
|
||||||
|
if self._thread is None or not self._thread.is_alive():
|
||||||
|
self._stop_event.clear()
|
||||||
|
self._thread = threading.Thread(target=self._run, daemon=True)
|
||||||
|
self._thread.start()
|
||||||
|
|
||||||
|
def pause(self):
|
||||||
|
self._play_event.clear()
|
||||||
|
self._ui_queue.put(("replay_state", "paused"))
|
||||||
|
|
||||||
|
def stop(self):
|
||||||
|
self._stop_event.set()
|
||||||
|
self._play_event.set() # unblock wait so thread exits promptly
|
||||||
|
with self._lock:
|
||||||
|
self._current_index = 0
|
||||||
|
self._last_emitted_index = -1
|
||||||
|
if self._thread is not None:
|
||||||
|
self._thread.join(timeout=2)
|
||||||
|
self._thread = None
|
||||||
|
self._play_event.clear()
|
||||||
|
self._ui_queue.put(("replay_state", "stopped"))
|
||||||
|
|
||||||
|
def close(self):
|
||||||
|
"""Stop playback and release underlying engine resources."""
|
||||||
|
self.stop()
|
||||||
|
if self._engine is not None:
|
||||||
|
self._engine.close()
|
||||||
|
self._engine = None
|
||||||
|
self._software_fpga = None
|
||||||
|
|
||||||
|
def seek(self, index: int):
|
||||||
|
with self._lock:
|
||||||
|
self._current_index = max(0, min(index, self.total_frames - 1))
|
||||||
|
self._emit_frame()
|
||||||
|
self._last_emitted_index = self._current_index
|
||||||
|
# Advance past the emitted frame so _run doesn't re-emit it
|
||||||
|
self._current_index += 1
|
||||||
|
|
||||||
|
def _run(self):
|
||||||
|
while not self._stop_event.is_set():
|
||||||
|
# Block until play or stop is signalled — no busy-sleep
|
||||||
|
self._play_event.wait()
|
||||||
|
if self._stop_event.is_set():
|
||||||
|
break
|
||||||
|
with self._lock:
|
||||||
|
if self._current_index >= self.total_frames:
|
||||||
|
if self._loop:
|
||||||
|
self._current_index = 0
|
||||||
|
else:
|
||||||
|
self._play_event.clear()
|
||||||
|
self._ui_queue.put(("replay_state", "paused"))
|
||||||
|
continue
|
||||||
|
self._emit_frame()
|
||||||
|
self._last_emitted_index = self._current_index
|
||||||
|
idx = self._current_index
|
||||||
|
self._current_index += 1
|
||||||
|
self._ui_queue.put(("replay_index", (idx, self.total_frames)))
|
||||||
|
time.sleep(self._frame_interval)
|
||||||
|
|
||||||
|
def _emit_frame(self):
|
||||||
|
"""Get current frame and push to queue. Must be called with lock held."""
|
||||||
|
if self._engine is None:
|
||||||
|
return
|
||||||
|
frame = self._engine.get_frame(self._current_index)
|
||||||
|
if frame is not None:
|
||||||
|
frame = copy.deepcopy(frame)
|
||||||
|
with contextlib.suppress(queue.Full):
|
||||||
|
self._frame_queue.put_nowait(frame)
|
||||||
|
|
||||||
|
|
||||||
class RadarDashboard:
|
class RadarDashboard:
|
||||||
"""Main tkinter application: real-time radar visualization and control."""
|
"""Main tkinter application: real-time radar visualization and control."""
|
||||||
|
|
||||||
@@ -93,7 +399,7 @@ class RadarDashboard:
|
|||||||
self.root.geometry("1600x950")
|
self.root.geometry("1600x950")
|
||||||
self.root.configure(bg=BG)
|
self.root.configure(bg=BG)
|
||||||
|
|
||||||
# Frame queue (acquisition → display)
|
# Frame queue (acquisition / replay / demo → display)
|
||||||
self.frame_queue: queue.Queue[RadarFrame] = queue.Queue(maxsize=8)
|
self.frame_queue: queue.Queue[RadarFrame] = queue.Queue(maxsize=8)
|
||||||
self._acq_thread: RadarAcquisition | None = None
|
self._acq_thread: RadarAcquisition | None = None
|
||||||
|
|
||||||
@@ -126,6 +432,17 @@ class RadarDashboard:
|
|||||||
self._agc_last_redraw: float = 0.0 # throttle chart redraws
|
self._agc_last_redraw: float = 0.0 # throttle chart redraws
|
||||||
self._AGC_REDRAW_INTERVAL: float = 0.5 # seconds between redraws
|
self._AGC_REDRAW_INTERVAL: float = 0.5 # seconds between redraws
|
||||||
|
|
||||||
|
# Replay state
|
||||||
|
self._replay_ctrl: _ReplayController | None = None
|
||||||
|
self._replay_active = False
|
||||||
|
|
||||||
|
# Demo state
|
||||||
|
self._demo_sim: DemoSimulator | None = None
|
||||||
|
self._demo_active = False
|
||||||
|
|
||||||
|
# Detected targets (from demo or replay host-DSP)
|
||||||
|
self._detected_targets: list[dict] = []
|
||||||
|
|
||||||
self._build_ui()
|
self._build_ui()
|
||||||
self._schedule_update()
|
self._schedule_update()
|
||||||
|
|
||||||
@@ -171,30 +488,33 @@ class RadarDashboard:
|
|||||||
self.btn_record = ttk.Button(top, text="Record", command=self._on_record)
|
self.btn_record = ttk.Button(top, text="Record", command=self._on_record)
|
||||||
self.btn_record.pack(side="right", padx=4)
|
self.btn_record.pack(side="right", padx=4)
|
||||||
|
|
||||||
|
self.btn_demo = ttk.Button(top, text="Start Demo",
|
||||||
|
command=self._toggle_demo)
|
||||||
|
self.btn_demo.pack(side="right", padx=4)
|
||||||
|
|
||||||
# -- Tabbed notebook layout --
|
# -- Tabbed notebook layout --
|
||||||
nb = ttk.Notebook(self.root)
|
nb = ttk.Notebook(self.root)
|
||||||
nb.pack(fill="both", expand=True, padx=8, pady=8)
|
nb.pack(fill="both", expand=True, padx=8, pady=8)
|
||||||
|
|
||||||
tab_display = ttk.Frame(nb)
|
tab_display = ttk.Frame(nb)
|
||||||
tab_control = ttk.Frame(nb)
|
tab_control = ttk.Frame(nb)
|
||||||
|
tab_replay = ttk.Frame(nb)
|
||||||
tab_agc = ttk.Frame(nb)
|
tab_agc = ttk.Frame(nb)
|
||||||
tab_log = ttk.Frame(nb)
|
tab_log = ttk.Frame(nb)
|
||||||
nb.add(tab_display, text=" Display ")
|
nb.add(tab_display, text=" Display ")
|
||||||
nb.add(tab_control, text=" Control ")
|
nb.add(tab_control, text=" Control ")
|
||||||
|
nb.add(tab_replay, text=" Replay ")
|
||||||
nb.add(tab_agc, text=" AGC Monitor ")
|
nb.add(tab_agc, text=" AGC Monitor ")
|
||||||
nb.add(tab_log, text=" Log ")
|
nb.add(tab_log, text=" Log ")
|
||||||
|
|
||||||
self._build_display_tab(tab_display)
|
self._build_display_tab(tab_display)
|
||||||
self._build_control_tab(tab_control)
|
self._build_control_tab(tab_control)
|
||||||
|
self._build_replay_tab(tab_replay)
|
||||||
self._build_agc_tab(tab_agc)
|
self._build_agc_tab(tab_agc)
|
||||||
self._build_log_tab(tab_log)
|
self._build_log_tab(tab_log)
|
||||||
|
|
||||||
def _build_display_tab(self, parent):
|
def _build_display_tab(self, parent):
|
||||||
# Compute physical axis limits
|
# Compute physical axis limits
|
||||||
# Range resolution: dR = c / (2 * BW) per range bin
|
|
||||||
# But we decimate 1024→64 bins, so each bin spans 16 FFT bins.
|
|
||||||
# Range resolution derivation: c/(2*BW) gives ~0.3 m per FFT bin.
|
|
||||||
# After 1024-to-64 decimation each displayed range bin spans 16 FFT bins.
|
|
||||||
range_res = self.C / (2.0 * self.BANDWIDTH) # ~0.3 m per FFT bin
|
range_res = self.C / (2.0 * self.BANDWIDTH) # ~0.3 m per FFT bin
|
||||||
# After decimation 1024→64, each range bin = 16 FFT bins
|
# After decimation 1024→64, each range bin = 16 FFT bins
|
||||||
range_per_bin = range_res * 16
|
range_per_bin = range_res * 16
|
||||||
@@ -203,8 +523,12 @@ class RadarDashboard:
|
|||||||
doppler_bin_lo = 0
|
doppler_bin_lo = 0
|
||||||
doppler_bin_hi = NUM_DOPPLER_BINS
|
doppler_bin_hi = NUM_DOPPLER_BINS
|
||||||
|
|
||||||
|
# Top pane: plots
|
||||||
|
plot_frame = ttk.Frame(parent)
|
||||||
|
plot_frame.pack(fill="both", expand=True)
|
||||||
|
|
||||||
# Matplotlib figure with 3 subplots
|
# Matplotlib figure with 3 subplots
|
||||||
self.fig = Figure(figsize=(14, 7), facecolor=BG)
|
self.fig = Figure(figsize=(14, 5), facecolor=BG)
|
||||||
self.fig.subplots_adjust(left=0.07, right=0.98, top=0.94, bottom=0.10,
|
self.fig.subplots_adjust(left=0.07, right=0.98, top=0.94, bottom=0.10,
|
||||||
wspace=0.30, hspace=0.35)
|
wspace=0.30, hspace=0.35)
|
||||||
|
|
||||||
@@ -245,11 +569,35 @@ class RadarDashboard:
|
|||||||
self.ax_wf.set_ylabel("Frame", color=FG)
|
self.ax_wf.set_ylabel("Frame", color=FG)
|
||||||
self.ax_wf.tick_params(colors=FG)
|
self.ax_wf.tick_params(colors=FG)
|
||||||
|
|
||||||
canvas = FigureCanvasTkAgg(self.fig, master=parent)
|
canvas = FigureCanvasTkAgg(self.fig, master=plot_frame)
|
||||||
canvas.draw()
|
canvas.draw()
|
||||||
canvas.get_tk_widget().pack(fill="both", expand=True)
|
canvas.get_tk_widget().pack(fill="both", expand=True)
|
||||||
self._canvas = canvas
|
self._canvas = canvas
|
||||||
|
|
||||||
|
# Bottom pane: detected targets table
|
||||||
|
tgt_frame = ttk.LabelFrame(parent, text="Detected Targets", padding=4)
|
||||||
|
tgt_frame.pack(fill="x", padx=8, pady=(0, 4))
|
||||||
|
|
||||||
|
cols = ("id", "range_m", "velocity", "azimuth", "snr", "class")
|
||||||
|
self._tgt_tree = ttk.Treeview(
|
||||||
|
tgt_frame, columns=cols, show="headings", height=5)
|
||||||
|
for col, heading, width in [
|
||||||
|
("id", "ID", 50),
|
||||||
|
("range_m", "Range (m)", 100),
|
||||||
|
("velocity", "Vel (m/s)", 90),
|
||||||
|
("azimuth", "Az (deg)", 90),
|
||||||
|
("snr", "SNR (dB)", 80),
|
||||||
|
("class", "Class", 100),
|
||||||
|
]:
|
||||||
|
self._tgt_tree.heading(col, text=heading)
|
||||||
|
self._tgt_tree.column(col, width=width, anchor="center")
|
||||||
|
|
||||||
|
scrollbar = ttk.Scrollbar(
|
||||||
|
tgt_frame, orient="vertical", command=self._tgt_tree.yview)
|
||||||
|
self._tgt_tree.configure(yscrollcommand=scrollbar.set)
|
||||||
|
self._tgt_tree.pack(side="left", fill="x", expand=True)
|
||||||
|
scrollbar.pack(side="right", fill="y")
|
||||||
|
|
||||||
def _build_control_tab(self, parent):
|
def _build_control_tab(self, parent):
|
||||||
"""Host command sender — organized by FPGA register groups.
|
"""Host command sender — organized by FPGA register groups.
|
||||||
|
|
||||||
@@ -492,6 +840,86 @@ class RadarDashboard:
|
|||||||
var.set(str(clamped))
|
var.set(str(clamped))
|
||||||
self._send_cmd(opcode, clamped)
|
self._send_cmd(opcode, clamped)
|
||||||
|
|
||||||
|
def _build_replay_tab(self, parent):
|
||||||
|
"""Replay tab — load file, transport controls, seek slider."""
|
||||||
|
# File selection
|
||||||
|
file_frame = ttk.LabelFrame(parent, text="Replay Source", padding=10)
|
||||||
|
file_frame.pack(fill="x", padx=8, pady=(8, 4))
|
||||||
|
|
||||||
|
self._replay_path_var = tk.StringVar(value="(none)")
|
||||||
|
ttk.Label(file_frame, textvariable=self._replay_path_var,
|
||||||
|
font=("Menlo", 9)).pack(side="left", fill="x", expand=True)
|
||||||
|
|
||||||
|
ttk.Button(file_frame, text="Browse File...",
|
||||||
|
command=self._replay_browse_file).pack(side="right", padx=(4, 0))
|
||||||
|
ttk.Button(file_frame, text="Browse Dir...",
|
||||||
|
command=self._replay_browse_dir).pack(side="right", padx=(4, 0))
|
||||||
|
|
||||||
|
# Transport controls
|
||||||
|
ctrl_frame = ttk.LabelFrame(parent, text="Transport", padding=10)
|
||||||
|
ctrl_frame.pack(fill="x", padx=8, pady=4)
|
||||||
|
|
||||||
|
btn_row = ttk.Frame(ctrl_frame)
|
||||||
|
btn_row.pack(fill="x", pady=(0, 6))
|
||||||
|
|
||||||
|
self._rp_play_btn = ttk.Button(
|
||||||
|
btn_row, text="Play", command=self._replay_play, state="disabled")
|
||||||
|
self._rp_play_btn.pack(side="left", padx=2)
|
||||||
|
|
||||||
|
self._rp_pause_btn = ttk.Button(
|
||||||
|
btn_row, text="Pause", command=self._replay_pause, state="disabled")
|
||||||
|
self._rp_pause_btn.pack(side="left", padx=2)
|
||||||
|
|
||||||
|
self._rp_stop_btn = ttk.Button(
|
||||||
|
btn_row, text="Stop", command=self._replay_stop, state="disabled")
|
||||||
|
self._rp_stop_btn.pack(side="left", padx=2)
|
||||||
|
|
||||||
|
# Speed selector
|
||||||
|
ttk.Label(btn_row, text="Speed:").pack(side="left", padx=(16, 4))
|
||||||
|
self._rp_speed_var = tk.StringVar(value="1x")
|
||||||
|
speed_combo = ttk.Combobox(
|
||||||
|
btn_row, textvariable=self._rp_speed_var,
|
||||||
|
values=list(_ReplayController.SPEED_MAP.keys()),
|
||||||
|
state="readonly", width=6)
|
||||||
|
speed_combo.pack(side="left", padx=2)
|
||||||
|
speed_combo.bind("<<ComboboxSelected>>", self._replay_speed_changed)
|
||||||
|
|
||||||
|
# Loop checkbox
|
||||||
|
self._rp_loop_var = tk.BooleanVar(value=False)
|
||||||
|
ttk.Checkbutton(btn_row, text="Loop",
|
||||||
|
variable=self._rp_loop_var,
|
||||||
|
command=self._replay_loop_changed).pack(side="left", padx=8)
|
||||||
|
|
||||||
|
# Seek slider
|
||||||
|
slider_row = ttk.Frame(ctrl_frame)
|
||||||
|
slider_row.pack(fill="x")
|
||||||
|
|
||||||
|
self._rp_slider = tk.Scale(
|
||||||
|
slider_row, from_=0, to=0, orient="horizontal",
|
||||||
|
bg=SURFACE, fg=FG, highlightthickness=0,
|
||||||
|
troughcolor=BG2, command=self._replay_seek)
|
||||||
|
self._rp_slider.pack(side="left", fill="x", expand=True)
|
||||||
|
|
||||||
|
self._rp_frame_label = ttk.Label(
|
||||||
|
slider_row, text="0 / 0", font=("Menlo", 10))
|
||||||
|
self._rp_frame_label.pack(side="right", padx=8)
|
||||||
|
|
||||||
|
# Status
|
||||||
|
self._rp_status_label = ttk.Label(
|
||||||
|
parent, text="No replay loaded", font=("Menlo", 10))
|
||||||
|
self._rp_status_label.pack(padx=8, pady=4, anchor="w")
|
||||||
|
|
||||||
|
# Info frame for FPGA controls during replay
|
||||||
|
info = ttk.LabelFrame(parent, text="Replay FPGA Controls", padding=10)
|
||||||
|
info.pack(fill="x", padx=8, pady=4)
|
||||||
|
ttk.Label(
|
||||||
|
info,
|
||||||
|
text=("When replaying Raw IQ data, FPGA Control tab "
|
||||||
|
"parameters are routed to the SoftwareFPGA.\n"
|
||||||
|
"Changes take effect on the next frame."),
|
||||||
|
font=("Menlo", 9), foreground=ACCENT,
|
||||||
|
).pack(anchor="w")
|
||||||
|
|
||||||
def _build_agc_tab(self, parent):
|
def _build_agc_tab(self, parent):
|
||||||
"""AGC Monitor tab — real-time strip charts for gain, peak, and saturation."""
|
"""AGC Monitor tab — real-time strip charts for gain, peak, and saturation."""
|
||||||
# Top row: AGC status badge + saturation indicator
|
# Top row: AGC status badge + saturation indicator
|
||||||
@@ -602,6 +1030,12 @@ class RadarDashboard:
|
|||||||
log.info("Disconnected")
|
log.info("Disconnected")
|
||||||
return
|
return
|
||||||
|
|
||||||
|
# Stop any active demo or replay before going live
|
||||||
|
if self._demo_active:
|
||||||
|
self._stop_demo()
|
||||||
|
if self._replay_active:
|
||||||
|
self._replay_stop()
|
||||||
|
|
||||||
# Open connection in a background thread to avoid blocking the GUI
|
# Open connection in a background thread to avoid blocking the GUI
|
||||||
self.lbl_status.config(text="CONNECTING...", foreground=YELLOW)
|
self.lbl_status.config(text="CONNECTING...", foreground=YELLOW)
|
||||||
self.btn_connect.config(state="disabled")
|
self.btn_connect.config(state="disabled")
|
||||||
@@ -644,7 +1078,37 @@ class RadarDashboard:
|
|||||||
self.recorder.start(filepath)
|
self.recorder.start(filepath)
|
||||||
self.btn_record.config(text="Stop Rec")
|
self.btn_record.config(text="Stop Rec")
|
||||||
|
|
||||||
|
# Opcode → SoftwareFPGA setter method name for dual dispatch during replay
|
||||||
|
_SFPGA_SETTER_NAMES: ClassVar[dict[int, str]] = {
|
||||||
|
0x03: "set_detect_threshold",
|
||||||
|
0x16: "set_gain_shift",
|
||||||
|
0x21: "set_cfar_guard",
|
||||||
|
0x22: "set_cfar_train",
|
||||||
|
0x23: "set_cfar_alpha",
|
||||||
|
0x24: "set_cfar_mode",
|
||||||
|
0x25: "set_cfar_enable",
|
||||||
|
0x26: "set_mti_enable",
|
||||||
|
0x27: "set_dc_notch_width",
|
||||||
|
0x28: "set_agc_enable",
|
||||||
|
}
|
||||||
|
|
||||||
def _send_cmd(self, opcode: int, value: int):
|
def _send_cmd(self, opcode: int, value: int):
|
||||||
|
"""Send command — routes to SoftwareFPGA when replaying raw IQ."""
|
||||||
|
if (self._replay_active and self._replay_ctrl is not None
|
||||||
|
and self._replay_ctrl.software_fpga is not None):
|
||||||
|
sfpga = self._replay_ctrl.software_fpga
|
||||||
|
setter_name = self._SFPGA_SETTER_NAMES.get(opcode)
|
||||||
|
if setter_name is not None:
|
||||||
|
getattr(sfpga, setter_name)(value)
|
||||||
|
log.info(
|
||||||
|
f"SoftwareFPGA 0x{opcode:02X} val={value}")
|
||||||
|
return
|
||||||
|
log.warning(
|
||||||
|
f"Opcode 0x{opcode:02X} not routable in replay mode")
|
||||||
|
self._ui_queue.put(
|
||||||
|
("status_msg",
|
||||||
|
f"Opcode 0x{opcode:02X} is hardware-only (ignored in replay)"))
|
||||||
|
return
|
||||||
cmd = RadarProtocol.build_command(opcode, value)
|
cmd = RadarProtocol.build_command(opcode, value)
|
||||||
ok = self.conn.write(cmd)
|
ok = self.conn.write(cmd)
|
||||||
log.info(f"CMD 0x{opcode:02X} val={value} ({'OK' if ok else 'FAIL'})")
|
log.info(f"CMD 0x{opcode:02X} val={value} ({'OK' if ok else 'FAIL'})")
|
||||||
@@ -657,6 +1121,133 @@ class RadarDashboard:
|
|||||||
except ValueError:
|
except ValueError:
|
||||||
log.error("Invalid custom command values")
|
log.error("Invalid custom command values")
|
||||||
|
|
||||||
|
# -------------------------------------------------------- Replay actions
|
||||||
|
def _replay_browse_file(self):
|
||||||
|
path = filedialog.askopenfilename(
|
||||||
|
title="Select replay file",
|
||||||
|
filetypes=[
|
||||||
|
("NumPy files", "*.npy"),
|
||||||
|
("HDF5 files", "*.h5"),
|
||||||
|
("All files", "*.*"),
|
||||||
|
],
|
||||||
|
)
|
||||||
|
if path:
|
||||||
|
self._replay_load(path)
|
||||||
|
|
||||||
|
def _replay_browse_dir(self):
|
||||||
|
path = filedialog.askdirectory(title="Select co-sim directory")
|
||||||
|
if path:
|
||||||
|
self._replay_load(path)
|
||||||
|
|
||||||
|
def _replay_load(self, path: str):
|
||||||
|
"""Load replay data and enable transport controls."""
|
||||||
|
# Stop any running mode
|
||||||
|
if self._demo_active:
|
||||||
|
self._stop_demo()
|
||||||
|
# Safely shutdown and disable UI controls before loading the new file
|
||||||
|
if self._replay_active or self._replay_ctrl is not None:
|
||||||
|
self._replay_stop()
|
||||||
|
if self._acq_thread is not None:
|
||||||
|
if self.conn.is_open:
|
||||||
|
self._on_connect() # disconnect
|
||||||
|
else:
|
||||||
|
# Connection dropped unexpectedly — just clean up the thread
|
||||||
|
self._acq_thread.stop()
|
||||||
|
self._acq_thread.join(timeout=2)
|
||||||
|
self._acq_thread = None
|
||||||
|
|
||||||
|
try:
|
||||||
|
self._replay_ctrl = _ReplayController(
|
||||||
|
self.frame_queue, self._ui_queue)
|
||||||
|
total = self._replay_ctrl.load(path)
|
||||||
|
except Exception as exc: # noqa: BLE001
|
||||||
|
log.error(f"Failed to load replay: {exc}")
|
||||||
|
self._rp_status_label.config(
|
||||||
|
text=f"Load failed: {exc}", foreground=RED)
|
||||||
|
self._replay_ctrl = None
|
||||||
|
return
|
||||||
|
|
||||||
|
short_path = Path(path).name
|
||||||
|
self._replay_path_var.set(short_path)
|
||||||
|
self._rp_slider.config(to=max(0, total - 1))
|
||||||
|
self._rp_frame_label.config(text=f"0 / {total}")
|
||||||
|
self._rp_status_label.config(
|
||||||
|
text=f"Loaded: {total} frames from {short_path}",
|
||||||
|
foreground=GREEN)
|
||||||
|
|
||||||
|
# Enable transport buttons
|
||||||
|
for btn in (self._rp_play_btn, self._rp_pause_btn, self._rp_stop_btn):
|
||||||
|
btn.config(state="normal")
|
||||||
|
|
||||||
|
self._replay_active = True
|
||||||
|
self.lbl_status.config(text="REPLAY", foreground=ACCENT)
|
||||||
|
log.info(f"Replay loaded: {total} frames from {path}")
|
||||||
|
|
||||||
|
def _replay_play(self):
|
||||||
|
if self._replay_ctrl:
|
||||||
|
self._replay_ctrl.play()
|
||||||
|
|
||||||
|
def _replay_pause(self):
|
||||||
|
if self._replay_ctrl:
|
||||||
|
self._replay_ctrl.pause()
|
||||||
|
|
||||||
|
def _replay_stop(self):
|
||||||
|
if self._replay_ctrl:
|
||||||
|
self._replay_ctrl.close()
|
||||||
|
self._replay_ctrl = None
|
||||||
|
self._replay_active = False
|
||||||
|
self.lbl_status.config(text="DISCONNECTED", foreground=RED)
|
||||||
|
self._rp_slider.set(0)
|
||||||
|
self._rp_frame_label.config(text="0 / 0")
|
||||||
|
for btn in (self._rp_play_btn, self._rp_pause_btn, self._rp_stop_btn):
|
||||||
|
btn.config(state="disabled")
|
||||||
|
|
||||||
|
def _replay_seek(self, value):
|
||||||
|
if (self._replay_ctrl and self._replay_active
|
||||||
|
and not self._replay_ctrl.is_playing):
|
||||||
|
self._replay_ctrl.seek(int(value))
|
||||||
|
|
||||||
|
def _replay_speed_changed(self, _event=None):
|
||||||
|
if self._replay_ctrl:
|
||||||
|
self._replay_ctrl.set_speed(self._rp_speed_var.get())
|
||||||
|
|
||||||
|
def _replay_loop_changed(self):
|
||||||
|
if self._replay_ctrl:
|
||||||
|
self._replay_ctrl.set_loop(self._rp_loop_var.get())
|
||||||
|
|
||||||
|
# ---------------------------------------------------------- Demo actions
|
||||||
|
def _toggle_demo(self):
|
||||||
|
if self._demo_active:
|
||||||
|
self._stop_demo()
|
||||||
|
else:
|
||||||
|
self._start_demo()
|
||||||
|
|
||||||
|
def _start_demo(self):
|
||||||
|
"""Start demo mode with synthetic targets."""
|
||||||
|
# Mutual exclusion
|
||||||
|
if self._replay_active:
|
||||||
|
self._replay_stop()
|
||||||
|
if self._acq_thread is not None:
|
||||||
|
log.warning("Cannot start demo while radar is connected")
|
||||||
|
return
|
||||||
|
|
||||||
|
self._demo_sim = DemoSimulator(
|
||||||
|
self.frame_queue, self._ui_queue, self.root, interval_ms=500)
|
||||||
|
self._demo_sim.start()
|
||||||
|
self._demo_active = True
|
||||||
|
self.lbl_status.config(text="DEMO", foreground=YELLOW)
|
||||||
|
self.btn_demo.config(text="Stop Demo")
|
||||||
|
log.info("Demo mode started")
|
||||||
|
|
||||||
|
def _stop_demo(self):
|
||||||
|
if self._demo_sim is not None:
|
||||||
|
self._demo_sim.stop()
|
||||||
|
self._demo_sim = None
|
||||||
|
self._demo_active = False
|
||||||
|
self.lbl_status.config(text="DISCONNECTED", foreground=RED)
|
||||||
|
self.btn_demo.config(text="Start Demo")
|
||||||
|
log.info("Demo mode stopped")
|
||||||
|
|
||||||
def _on_status_received(self, status: StatusResponse):
|
def _on_status_received(self, status: StatusResponse):
|
||||||
"""Called from acquisition thread — post to UI queue for main thread."""
|
"""Called from acquisition thread — post to UI queue for main thread."""
|
||||||
self._ui_queue.put(("status", status))
|
self._ui_queue.put(("status", status))
|
||||||
@@ -804,6 +1395,46 @@ class RadarDashboard:
|
|||||||
self._update_self_test_labels(payload)
|
self._update_self_test_labels(payload)
|
||||||
elif tag == "log":
|
elif tag == "log":
|
||||||
self._log_handler_append(payload)
|
self._log_handler_append(payload)
|
||||||
|
elif tag == "replay_state":
|
||||||
|
self._on_replay_state(payload)
|
||||||
|
elif tag == "replay_index":
|
||||||
|
self._on_replay_index(*payload)
|
||||||
|
elif tag == "demo_targets":
|
||||||
|
self._on_demo_targets(payload)
|
||||||
|
elif tag == "status_msg":
|
||||||
|
self.lbl_status.config(text=str(payload), foreground=YELLOW)
|
||||||
|
|
||||||
|
def _on_replay_state(self, state: str):
|
||||||
|
if state == "playing":
|
||||||
|
self._rp_status_label.config(text="Playing", foreground=GREEN)
|
||||||
|
elif state == "paused":
|
||||||
|
self._rp_status_label.config(text="Paused", foreground=YELLOW)
|
||||||
|
elif state == "stopped":
|
||||||
|
self._rp_status_label.config(text="Stopped", foreground=FG)
|
||||||
|
|
||||||
|
def _on_replay_index(self, index: int, total: int):
|
||||||
|
self._rp_frame_label.config(text=f"{index} / {total}")
|
||||||
|
self._rp_slider.set(index)
|
||||||
|
|
||||||
|
def _on_demo_targets(self, targets: list[dict]):
|
||||||
|
"""Update the detected targets treeview from demo data."""
|
||||||
|
self._update_targets_table(targets)
|
||||||
|
|
||||||
|
def _update_targets_table(self, targets: list[dict]):
|
||||||
|
"""Refresh the detected targets treeview."""
|
||||||
|
# Clear existing rows
|
||||||
|
for item in self._tgt_tree.get_children():
|
||||||
|
self._tgt_tree.delete(item)
|
||||||
|
# Insert new rows
|
||||||
|
for t in targets:
|
||||||
|
self._tgt_tree.insert("", "end", values=(
|
||||||
|
t.get("id", ""),
|
||||||
|
f"{t.get('range_m', 0):.0f}",
|
||||||
|
f"{t.get('velocity', 0):.1f}",
|
||||||
|
f"{t.get('azimuth', 0):.1f}",
|
||||||
|
f"{t.get('snr', 0):.1f}",
|
||||||
|
t.get("class", ""),
|
||||||
|
))
|
||||||
|
|
||||||
def _log_handler_append(self, msg: str):
|
def _log_handler_append(self, msg: str):
|
||||||
"""Append a log message to the log Text widget (main thread only)."""
|
"""Append a log message to the log Text widget (main thread only)."""
|
||||||
@@ -902,24 +1533,20 @@ class _TextHandler(logging.Handler):
|
|||||||
|
|
||||||
def main():
|
def main():
|
||||||
parser = argparse.ArgumentParser(description="AERIS-10 Radar Dashboard")
|
parser = argparse.ArgumentParser(description="AERIS-10 Radar Dashboard")
|
||||||
parser.add_argument("--live", action="store_true",
|
|
||||||
help="Use real FT2232H hardware (default: mock mode)")
|
|
||||||
parser.add_argument("--replay", type=str, metavar="NPY_DIR",
|
|
||||||
help="Replay real data from .npy directory "
|
|
||||||
"(e.g. tb/cosim/real_data/hex/)")
|
|
||||||
parser.add_argument("--no-mti", action="store_true",
|
|
||||||
help="With --replay, use non-MTI Doppler data")
|
|
||||||
parser.add_argument("--record", action="store_true",
|
parser.add_argument("--record", action="store_true",
|
||||||
help="Start HDF5 recording immediately")
|
help="Start HDF5 recording immediately")
|
||||||
parser.add_argument("--device", type=int, default=0,
|
parser.add_argument("--device", type=int, default=0,
|
||||||
help="FT2232H device index (default: 0)")
|
help="FT2232H device index (default: 0)")
|
||||||
|
mode_group = parser.add_mutually_exclusive_group()
|
||||||
|
mode_group.add_argument("--live", action="store_true",
|
||||||
|
help="Use real FT2232H hardware (default: mock mode)")
|
||||||
|
mode_group.add_argument("--replay", type=str, default=None,
|
||||||
|
help="Auto-load replay file or directory on startup")
|
||||||
|
mode_group.add_argument("--demo", action="store_true",
|
||||||
|
help="Start in demo mode with synthetic targets")
|
||||||
args = parser.parse_args()
|
args = parser.parse_args()
|
||||||
|
|
||||||
if args.replay:
|
if args.live:
|
||||||
npy_dir = os.path.abspath(args.replay)
|
|
||||||
conn = ReplayConnection(npy_dir, use_mti=not args.no_mti)
|
|
||||||
mode_str = f"REPLAY ({npy_dir}, MTI={'OFF' if args.no_mti else 'ON'})"
|
|
||||||
elif args.live:
|
|
||||||
conn = FT2232HConnection(mock=False)
|
conn = FT2232HConnection(mock=False)
|
||||||
mode_str = "LIVE"
|
mode_str = "LIVE"
|
||||||
else:
|
else:
|
||||||
@@ -939,7 +1566,19 @@ def main():
|
|||||||
)
|
)
|
||||||
recorder.start(filepath)
|
recorder.start(filepath)
|
||||||
|
|
||||||
|
if args.replay:
|
||||||
|
dashboard._replay_load(args.replay)
|
||||||
|
|
||||||
|
if args.demo:
|
||||||
|
dashboard._start_demo()
|
||||||
|
|
||||||
def on_closing():
|
def on_closing():
|
||||||
|
# Stop demo if active
|
||||||
|
if dashboard._demo_active:
|
||||||
|
dashboard._stop_demo()
|
||||||
|
# Stop replay if active
|
||||||
|
if dashboard._replay_ctrl is not None:
|
||||||
|
dashboard._replay_ctrl.close()
|
||||||
if dashboard._acq_thread is not None:
|
if dashboard._acq_thread is not None:
|
||||||
dashboard._acq_thread.stop()
|
dashboard._acq_thread.stop()
|
||||||
dashboard._acq_thread.join(timeout=2)
|
dashboard._acq_thread.join(timeout=2)
|
||||||
@@ -8,6 +8,6 @@ GUI_V5 ==> Added Mercury Color
|
|||||||
|
|
||||||
GUI_V6 ==> Added USB3 FT601 support
|
GUI_V6 ==> Added USB3 FT601 support
|
||||||
|
|
||||||
radar_dashboard ==> Board bring-up dashboard (FT2232H reader, real-time R-D heatmap, CFAR overlay, waterfall, host commands, HDF5 recording)
|
GUI_V65_Tk ==> Board bring-up dashboard (FT2232H reader, real-time R-D heatmap, CFAR overlay, waterfall, host commands, HDF5 recording, replay, demo mode)
|
||||||
radar_protocol ==> Protocol layer (packet parsing, command building, FT2232H connection, data recorder, acquisition thread)
|
radar_protocol ==> Protocol layer (packet parsing, command building, FT2232H connection, data recorder, acquisition thread)
|
||||||
smoke_test ==> Board bring-up smoke test host script (triggers FPGA self-test via opcode 0x30)
|
smoke_test ==> Board bring-up smoke test host script (triggers FPGA self-test via opcode 0x30)
|
||||||
|
|||||||
@@ -32,83 +32,24 @@ from pathlib import Path
|
|||||||
import matplotlib.pyplot as plt
|
import matplotlib.pyplot as plt
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|
||||||
|
from v7.agc_sim import (
|
||||||
|
encoding_to_signed,
|
||||||
|
apply_gain_shift,
|
||||||
|
quantize_iq,
|
||||||
|
AGCConfig,
|
||||||
|
AGCState,
|
||||||
|
process_agc_frame,
|
||||||
|
)
|
||||||
|
|
||||||
# ---------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------
|
||||||
# FPGA AGC parameters (rx_gain_control.v reset defaults)
|
# FPGA AGC parameters (rx_gain_control.v reset defaults)
|
||||||
# ---------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------
|
||||||
AGC_TARGET = 200 # host_agc_target (8-bit, default 200)
|
AGC_TARGET = 200 # host_agc_target (8-bit, default 200)
|
||||||
AGC_ATTACK = 1 # host_agc_attack (4-bit, default 1)
|
|
||||||
AGC_DECAY = 1 # host_agc_decay (4-bit, default 1)
|
|
||||||
AGC_HOLDOFF = 4 # host_agc_holdoff (4-bit, default 4)
|
|
||||||
ADC_RAIL = 4095 # 12-bit ADC max absolute value
|
ADC_RAIL = 4095 # 12-bit ADC max absolute value
|
||||||
|
|
||||||
|
|
||||||
# ---------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------
|
||||||
# Gain encoding helpers (match RTL signed_to_encoding / encoding_to_signed)
|
# Per-frame AGC simulation using v7.agc_sim (bit-accurate to RTL)
|
||||||
# ---------------------------------------------------------------------------
|
|
||||||
|
|
||||||
def signed_to_encoding(g: int) -> int:
|
|
||||||
"""Convert signed gain (-7..+7) to gain_shift[3:0] encoding.
|
|
||||||
[3]=0, [2:0]=N → amplify (left shift) by N
|
|
||||||
[3]=1, [2:0]=N → attenuate (right shift) by N
|
|
||||||
"""
|
|
||||||
if g >= 0:
|
|
||||||
return g & 0x07
|
|
||||||
return 0x08 | ((-g) & 0x07)
|
|
||||||
|
|
||||||
|
|
||||||
def encoding_to_signed(enc: int) -> int:
|
|
||||||
"""Convert gain_shift[3:0] encoding to signed gain."""
|
|
||||||
if (enc & 0x08) == 0:
|
|
||||||
return enc & 0x07
|
|
||||||
return -(enc & 0x07)
|
|
||||||
|
|
||||||
|
|
||||||
def clamp_gain(val: int) -> int:
|
|
||||||
"""Clamp to [-7, +7] (matches RTL clamp_gain function)."""
|
|
||||||
return max(-7, min(7, val))
|
|
||||||
|
|
||||||
|
|
||||||
# ---------------------------------------------------------------------------
|
|
||||||
# Apply gain shift to IQ data (matches RTL combinational logic)
|
|
||||||
# ---------------------------------------------------------------------------
|
|
||||||
|
|
||||||
def apply_gain_shift(frame_i: np.ndarray, frame_q: np.ndarray,
|
|
||||||
gain_enc: int) -> tuple[np.ndarray, np.ndarray, int]:
|
|
||||||
"""Apply gain_shift encoding to 16-bit signed IQ arrays.
|
|
||||||
|
|
||||||
Returns (shifted_i, shifted_q, overflow_count).
|
|
||||||
Matches the RTL: left shift = amplify, right shift = attenuate,
|
|
||||||
saturate to ±32767 on overflow.
|
|
||||||
"""
|
|
||||||
direction = (gain_enc >> 3) & 1 # 0=amplify, 1=attenuate
|
|
||||||
amount = gain_enc & 0x07
|
|
||||||
|
|
||||||
if amount == 0:
|
|
||||||
return frame_i.copy(), frame_q.copy(), 0
|
|
||||||
|
|
||||||
if direction == 0:
|
|
||||||
# Left shift (amplify)
|
|
||||||
si = frame_i.astype(np.int64) * (1 << amount)
|
|
||||||
sq = frame_q.astype(np.int64) * (1 << amount)
|
|
||||||
else:
|
|
||||||
# Arithmetic right shift (attenuate)
|
|
||||||
si = frame_i.astype(np.int64) >> amount
|
|
||||||
sq = frame_q.astype(np.int64) >> amount
|
|
||||||
|
|
||||||
# Count overflows (post-shift values outside 16-bit signed range)
|
|
||||||
overflow_i = (si > 32767) | (si < -32768)
|
|
||||||
overflow_q = (sq > 32767) | (sq < -32768)
|
|
||||||
overflow_count = int((overflow_i | overflow_q).sum())
|
|
||||||
|
|
||||||
# Saturate to ±32767
|
|
||||||
si = np.clip(si, -32768, 32767).astype(np.int16)
|
|
||||||
sq = np.clip(sq, -32768, 32767).astype(np.int16)
|
|
||||||
|
|
||||||
return si, sq, overflow_count
|
|
||||||
|
|
||||||
|
|
||||||
# ---------------------------------------------------------------------------
|
|
||||||
# Per-frame AGC simulation (bit-accurate to rx_gain_control.v)
|
|
||||||
# ---------------------------------------------------------------------------
|
# ---------------------------------------------------------------------------
|
||||||
|
|
||||||
def simulate_agc(frames: np.ndarray, agc_enabled: bool = True,
|
def simulate_agc(frames: np.ndarray, agc_enabled: bool = True,
|
||||||
@@ -126,79 +67,46 @@ def simulate_agc(frames: np.ndarray, agc_enabled: bool = True,
|
|||||||
n_frames = frames.shape[0]
|
n_frames = frames.shape[0]
|
||||||
|
|
||||||
# Output arrays
|
# Output arrays
|
||||||
out_gain_enc = np.zeros(n_frames, dtype=int) # gain_shift encoding [3:0]
|
out_gain_enc = np.zeros(n_frames, dtype=int)
|
||||||
out_gain_signed = np.zeros(n_frames, dtype=int) # signed gain for plotting
|
out_gain_signed = np.zeros(n_frames, dtype=int)
|
||||||
out_peak_mag = np.zeros(n_frames, dtype=int) # peak_magnitude[7:0]
|
out_peak_mag = np.zeros(n_frames, dtype=int)
|
||||||
out_sat_count = np.zeros(n_frames, dtype=int) # saturation_count[7:0]
|
out_sat_count = np.zeros(n_frames, dtype=int)
|
||||||
out_sat_rate = np.zeros(n_frames, dtype=float)
|
out_sat_rate = np.zeros(n_frames, dtype=float)
|
||||||
out_rms_post = np.zeros(n_frames, dtype=float) # RMS after gain shift
|
out_rms_post = np.zeros(n_frames, dtype=float)
|
||||||
|
|
||||||
# AGC internal state
|
# AGC state — managed by process_agc_frame()
|
||||||
agc_gain = 0 # signed, -7..+7
|
state = AGCState(
|
||||||
holdoff_counter = 0
|
gain=encoding_to_signed(initial_gain_enc),
|
||||||
agc_was_enabled = False
|
holdoff_counter=0,
|
||||||
|
was_enabled=False,
|
||||||
|
)
|
||||||
|
|
||||||
for i in range(n_frames):
|
for i in range(n_frames):
|
||||||
frame = frames[i]
|
frame_i, frame_q = quantize_iq(frames[i])
|
||||||
# Quantize to 16-bit signed (ADC is 12-bit, sign-extended to 16)
|
|
||||||
frame_i = np.clip(np.round(frame.real), -32768, 32767).astype(np.int16)
|
|
||||||
frame_q = np.clip(np.round(frame.imag), -32768, 32767).astype(np.int16)
|
|
||||||
|
|
||||||
# --- PRE-gain peak measurement (RTL lines 133-135, 211-213) ---
|
|
||||||
abs_i = np.abs(frame_i.astype(np.int32))
|
|
||||||
abs_q = np.abs(frame_q.astype(np.int32))
|
|
||||||
max_iq = np.maximum(abs_i, abs_q)
|
|
||||||
frame_peak_15bit = int(max_iq.max()) # 15-bit unsigned
|
|
||||||
peak_8bit = (frame_peak_15bit >> 7) & 0xFF # Upper 8 bits
|
|
||||||
|
|
||||||
# --- Determine effective gain ---
|
|
||||||
agc_active = agc_enabled and (i >= enable_at_frame)
|
agc_active = agc_enabled and (i >= enable_at_frame)
|
||||||
|
|
||||||
# AGC enable transition (RTL lines 250-253)
|
# Build per-frame config (enable toggles at enable_at_frame)
|
||||||
if agc_active and not agc_was_enabled:
|
config = AGCConfig(enabled=agc_active)
|
||||||
agc_gain = encoding_to_signed(initial_gain_enc)
|
|
||||||
holdoff_counter = AGC_HOLDOFF
|
|
||||||
|
|
||||||
effective_enc = signed_to_encoding(agc_gain) if agc_active else initial_gain_enc
|
result = process_agc_frame(frame_i, frame_q, config, state)
|
||||||
|
|
||||||
agc_was_enabled = agc_active
|
|
||||||
|
|
||||||
# --- Apply gain shift + count POST-gain overflow (RTL lines 114-126, 207-209) ---
|
|
||||||
shifted_i, shifted_q, frame_overflow = apply_gain_shift(
|
|
||||||
frame_i, frame_q, effective_enc)
|
|
||||||
frame_sat = min(255, frame_overflow)
|
|
||||||
|
|
||||||
# RMS of shifted signal
|
# RMS of shifted signal
|
||||||
rms = float(np.sqrt(np.mean(
|
rms = float(np.sqrt(np.mean(
|
||||||
shifted_i.astype(np.float64)**2 + shifted_q.astype(np.float64)**2)))
|
result.shifted_i.astype(np.float64)**2
|
||||||
|
+ result.shifted_q.astype(np.float64)**2)))
|
||||||
|
|
||||||
total_samples = frame_i.size + frame_q.size
|
total_samples = frame_i.size + frame_q.size
|
||||||
sat_rate = frame_overflow / total_samples if total_samples > 0 else 0.0
|
sat_rate = result.overflow_raw / total_samples if total_samples > 0 else 0.0
|
||||||
|
|
||||||
# --- Record outputs ---
|
# Record outputs
|
||||||
out_gain_enc[i] = effective_enc
|
out_gain_enc[i] = result.gain_enc
|
||||||
out_gain_signed[i] = agc_gain if agc_active else encoding_to_signed(initial_gain_enc)
|
out_gain_signed[i] = result.gain_signed
|
||||||
out_peak_mag[i] = peak_8bit
|
out_peak_mag[i] = result.peak_mag_8bit
|
||||||
out_sat_count[i] = frame_sat
|
out_sat_count[i] = result.saturation_count
|
||||||
out_sat_rate[i] = sat_rate
|
out_sat_rate[i] = sat_rate
|
||||||
out_rms_post[i] = rms
|
out_rms_post[i] = rms
|
||||||
|
|
||||||
# --- AGC update at frame boundary (RTL lines 226-246) ---
|
|
||||||
if agc_active:
|
|
||||||
if frame_sat > 0:
|
|
||||||
# Clipping: reduce gain immediately (attack)
|
|
||||||
agc_gain = clamp_gain(agc_gain - AGC_ATTACK)
|
|
||||||
holdoff_counter = AGC_HOLDOFF
|
|
||||||
elif peak_8bit < AGC_TARGET:
|
|
||||||
# Signal too weak: increase gain after holdoff
|
|
||||||
if holdoff_counter == 0:
|
|
||||||
agc_gain = clamp_gain(agc_gain + AGC_DECAY)
|
|
||||||
else:
|
|
||||||
holdoff_counter -= 1
|
|
||||||
else:
|
|
||||||
# Good range (peak >= target, no sat): hold, reset holdoff
|
|
||||||
holdoff_counter = AGC_HOLDOFF
|
|
||||||
|
|
||||||
return {
|
return {
|
||||||
"gain_enc": out_gain_enc,
|
"gain_enc": out_gain_enc,
|
||||||
"gain_signed": out_gain_signed,
|
"gain_signed": out_gain_signed,
|
||||||
@@ -217,8 +125,7 @@ def process_frame_rd(frame: np.ndarray, gain_enc: int,
|
|||||||
n_range: int = 64,
|
n_range: int = 64,
|
||||||
n_doppler: int = 32) -> np.ndarray:
|
n_doppler: int = 32) -> np.ndarray:
|
||||||
"""Range-Doppler magnitude for one frame with gain applied."""
|
"""Range-Doppler magnitude for one frame with gain applied."""
|
||||||
frame_i = np.clip(np.round(frame.real), -32768, 32767).astype(np.int16)
|
frame_i, frame_q = quantize_iq(frame)
|
||||||
frame_q = np.clip(np.round(frame.imag), -32768, 32767).astype(np.int16)
|
|
||||||
si, sq, _ = apply_gain_shift(frame_i, frame_q, gain_enc)
|
si, sq, _ = apply_gain_shift(frame_i, frame_q, gain_enc)
|
||||||
|
|
||||||
iq = si.astype(np.float64) + 1j * sq.astype(np.float64)
|
iq = si.astype(np.float64) + 1j * sq.astype(np.float64)
|
||||||
|
|||||||
@@ -15,7 +15,6 @@ USB Packet Protocol (11-byte):
|
|||||||
Command: 4 bytes received sequentially {opcode, addr, value_hi, value_lo}
|
Command: 4 bytes received sequentially {opcode, addr, value_hi, value_lo}
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import os
|
|
||||||
import struct
|
import struct
|
||||||
import time
|
import time
|
||||||
import threading
|
import threading
|
||||||
@@ -443,391 +442,7 @@ class FT2232HConnection:
|
|||||||
return bytes(buf)
|
return bytes(buf)
|
||||||
|
|
||||||
|
|
||||||
# ============================================================================
|
|
||||||
# Replay Connection — feed real .npy data through the dashboard
|
|
||||||
# ============================================================================
|
|
||||||
|
|
||||||
# Hardware-only opcodes that cannot be adjusted in replay mode
|
|
||||||
# Values must match radar_system_top.v case(usb_cmd_opcode).
|
|
||||||
_HARDWARE_ONLY_OPCODES = {
|
|
||||||
0x01, # RADAR_MODE
|
|
||||||
0x02, # TRIGGER_PULSE
|
|
||||||
# 0x03 (DETECT_THRESHOLD) is NOT hardware-only — it's in _REPLAY_ADJUSTABLE_OPCODES
|
|
||||||
0x04, # STREAM_CONTROL
|
|
||||||
0x10, # LONG_CHIRP
|
|
||||||
0x11, # LONG_LISTEN
|
|
||||||
0x12, # GUARD
|
|
||||||
0x13, # SHORT_CHIRP
|
|
||||||
0x14, # SHORT_LISTEN
|
|
||||||
0x15, # CHIRPS_PER_ELEV
|
|
||||||
0x16, # GAIN_SHIFT
|
|
||||||
0x20, # RANGE_MODE
|
|
||||||
0x28, # AGC_ENABLE
|
|
||||||
0x29, # AGC_TARGET
|
|
||||||
0x2A, # AGC_ATTACK
|
|
||||||
0x2B, # AGC_DECAY
|
|
||||||
0x2C, # AGC_HOLDOFF
|
|
||||||
0x30, # SELF_TEST_TRIGGER
|
|
||||||
0x31, # SELF_TEST_STATUS
|
|
||||||
0xFF, # STATUS_REQUEST
|
|
||||||
}
|
|
||||||
|
|
||||||
# Replay-adjustable opcodes (re-run signal processing)
|
|
||||||
_REPLAY_ADJUSTABLE_OPCODES = {
|
|
||||||
0x03, # DETECT_THRESHOLD
|
|
||||||
0x21, # CFAR_GUARD
|
|
||||||
0x22, # CFAR_TRAIN
|
|
||||||
0x23, # CFAR_ALPHA
|
|
||||||
0x24, # CFAR_MODE
|
|
||||||
0x25, # CFAR_ENABLE
|
|
||||||
0x26, # MTI_ENABLE
|
|
||||||
0x27, # DC_NOTCH_WIDTH
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
def _saturate(val: int, bits: int) -> int:
|
|
||||||
"""Saturate signed value to fit in 'bits' width."""
|
|
||||||
max_pos = (1 << (bits - 1)) - 1
|
|
||||||
max_neg = -(1 << (bits - 1))
|
|
||||||
return max(max_neg, min(max_pos, int(val)))
|
|
||||||
|
|
||||||
|
|
||||||
def _replay_dc_notch(doppler_i: np.ndarray, doppler_q: np.ndarray,
|
|
||||||
width: int) -> tuple[np.ndarray, np.ndarray]:
|
|
||||||
"""Bit-accurate DC notch filter (matches radar_system_top.v inline).
|
|
||||||
|
|
||||||
Dual sub-frame notch: doppler_bin[4:0] = {sub_frame, bin[3:0]}.
|
|
||||||
Each 16-bin sub-frame has its own DC at bin 0, so we zero bins
|
|
||||||
where ``bin_within_sf < width`` or ``bin_within_sf > (15 - width + 1)``.
|
|
||||||
"""
|
|
||||||
out_i = doppler_i.copy()
|
|
||||||
out_q = doppler_q.copy()
|
|
||||||
if width == 0:
|
|
||||||
return out_i, out_q
|
|
||||||
n_doppler = doppler_i.shape[1]
|
|
||||||
for dbin in range(n_doppler):
|
|
||||||
bin_within_sf = dbin & 0xF
|
|
||||||
if bin_within_sf < width or bin_within_sf > (15 - width + 1):
|
|
||||||
out_i[:, dbin] = 0
|
|
||||||
out_q[:, dbin] = 0
|
|
||||||
return out_i, out_q
|
|
||||||
|
|
||||||
|
|
||||||
def _replay_cfar(doppler_i: np.ndarray, doppler_q: np.ndarray,
|
|
||||||
guard: int, train: int, alpha_q44: int,
|
|
||||||
mode: int) -> tuple[np.ndarray, np.ndarray]:
|
|
||||||
"""
|
|
||||||
Bit-accurate CA-CFAR detector (matches cfar_ca.v).
|
|
||||||
Returns (detect_flags, magnitudes) both (64, 32).
|
|
||||||
"""
|
|
||||||
ALPHA_FRAC_BITS = 4
|
|
||||||
n_range, n_doppler = doppler_i.shape
|
|
||||||
if train == 0:
|
|
||||||
train = 1
|
|
||||||
|
|
||||||
# Compute magnitudes: |I| + |Q| (17-bit unsigned L1 norm)
|
|
||||||
magnitudes = np.zeros((n_range, n_doppler), dtype=np.int64)
|
|
||||||
for r in range(n_range):
|
|
||||||
for d in range(n_doppler):
|
|
||||||
i_val = int(doppler_i[r, d])
|
|
||||||
q_val = int(doppler_q[r, d])
|
|
||||||
abs_i = (-i_val) & 0xFFFF if i_val < 0 else i_val & 0xFFFF
|
|
||||||
abs_q = (-q_val) & 0xFFFF if q_val < 0 else q_val & 0xFFFF
|
|
||||||
magnitudes[r, d] = abs_i + abs_q
|
|
||||||
|
|
||||||
detect_flags = np.zeros((n_range, n_doppler), dtype=np.bool_)
|
|
||||||
MAX_MAG = (1 << 17) - 1
|
|
||||||
|
|
||||||
mode_names = {0: 'CA', 1: 'GO', 2: 'SO'}
|
|
||||||
mode_str = mode_names.get(mode, 'CA')
|
|
||||||
|
|
||||||
for dbin in range(n_doppler):
|
|
||||||
col = magnitudes[:, dbin]
|
|
||||||
for cut in range(n_range):
|
|
||||||
lead_sum, lead_cnt = 0, 0
|
|
||||||
for t in range(1, train + 1):
|
|
||||||
idx = cut - guard - t
|
|
||||||
if 0 <= idx < n_range:
|
|
||||||
lead_sum += int(col[idx])
|
|
||||||
lead_cnt += 1
|
|
||||||
lag_sum, lag_cnt = 0, 0
|
|
||||||
for t in range(1, train + 1):
|
|
||||||
idx = cut + guard + t
|
|
||||||
if 0 <= idx < n_range:
|
|
||||||
lag_sum += int(col[idx])
|
|
||||||
lag_cnt += 1
|
|
||||||
|
|
||||||
if mode_str == 'CA':
|
|
||||||
noise = lead_sum + lag_sum
|
|
||||||
elif mode_str == 'GO':
|
|
||||||
if lead_cnt > 0 and lag_cnt > 0:
|
|
||||||
noise = lead_sum if lead_sum * lag_cnt > lag_sum * lead_cnt else lag_sum
|
|
||||||
else:
|
|
||||||
noise = lead_sum if lead_cnt > 0 else lag_sum
|
|
||||||
elif mode_str == 'SO':
|
|
||||||
if lead_cnt > 0 and lag_cnt > 0:
|
|
||||||
noise = lead_sum if lead_sum * lag_cnt < lag_sum * lead_cnt else lag_sum
|
|
||||||
else:
|
|
||||||
noise = lead_sum if lead_cnt > 0 else lag_sum
|
|
||||||
else:
|
|
||||||
noise = lead_sum + lag_sum
|
|
||||||
|
|
||||||
thr = min((alpha_q44 * noise) >> ALPHA_FRAC_BITS, MAX_MAG)
|
|
||||||
if int(col[cut]) > thr:
|
|
||||||
detect_flags[cut, dbin] = True
|
|
||||||
|
|
||||||
return detect_flags, magnitudes
|
|
||||||
|
|
||||||
|
|
||||||
class ReplayConnection:
|
|
||||||
"""
|
|
||||||
Loads pre-computed .npy arrays (from golden_reference.py co-sim output)
|
|
||||||
and serves them as USB data packets to the dashboard, exercising the full
|
|
||||||
parsing pipeline with real ADI CN0566 radar data.
|
|
||||||
|
|
||||||
Signal processing parameters (CFAR guard/train/alpha/mode, MTI enable,
|
|
||||||
DC notch width) can be adjusted at runtime via write() — the connection
|
|
||||||
re-runs the bit-accurate processing pipeline and rebuilds packets.
|
|
||||||
|
|
||||||
Required npy directory layout (e.g. tb/cosim/real_data/hex/):
|
|
||||||
decimated_range_i.npy (32, 64) int — pre-Doppler range I
|
|
||||||
decimated_range_q.npy (32, 64) int — pre-Doppler range Q
|
|
||||||
doppler_map_i.npy (64, 32) int — Doppler I (no MTI)
|
|
||||||
doppler_map_q.npy (64, 32) int — Doppler Q (no MTI)
|
|
||||||
fullchain_mti_doppler_i.npy (64, 32) int — Doppler I (with MTI)
|
|
||||||
fullchain_mti_doppler_q.npy (64, 32) int — Doppler Q (with MTI)
|
|
||||||
fullchain_cfar_flags.npy (64, 32) bool — CFAR detections
|
|
||||||
fullchain_cfar_mag.npy (64, 32) int — CFAR |I|+|Q| magnitude
|
|
||||||
"""
|
|
||||||
|
|
||||||
def __init__(self, npy_dir: str, use_mti: bool = True,
|
|
||||||
replay_fps: float = 5.0):
|
|
||||||
self._npy_dir = npy_dir
|
|
||||||
self._use_mti = use_mti
|
|
||||||
self._replay_fps = max(replay_fps, 0.1)
|
|
||||||
self._lock = threading.Lock()
|
|
||||||
self.is_open = False
|
|
||||||
self._packets: bytes = b""
|
|
||||||
self._read_offset = 0
|
|
||||||
self._frame_len = 0
|
|
||||||
# Current signal-processing parameters
|
|
||||||
self._mti_enable: bool = use_mti
|
|
||||||
self._dc_notch_width: int = 2
|
|
||||||
self._cfar_guard: int = 2
|
|
||||||
self._cfar_train: int = 8
|
|
||||||
self._cfar_alpha: int = 0x30
|
|
||||||
self._cfar_mode: int = 0 # 0=CA, 1=GO, 2=SO
|
|
||||||
self._cfar_enable: bool = True
|
|
||||||
self._detect_threshold: int = 10000 # RTL default (host_detect_threshold)
|
|
||||||
# Raw source arrays (loaded once, reprocessed on param change)
|
|
||||||
self._dop_mti_i: np.ndarray | None = None
|
|
||||||
self._dop_mti_q: np.ndarray | None = None
|
|
||||||
self._dop_nomti_i: np.ndarray | None = None
|
|
||||||
self._dop_nomti_q: np.ndarray | None = None
|
|
||||||
self._range_i_vec: np.ndarray | None = None
|
|
||||||
self._range_q_vec: np.ndarray | None = None
|
|
||||||
# Rebuild flag
|
|
||||||
self._needs_rebuild = False
|
|
||||||
|
|
||||||
def open(self, _device_index: int = 0) -> bool:
|
|
||||||
try:
|
|
||||||
self._load_arrays()
|
|
||||||
self._packets = self._build_packets()
|
|
||||||
self._frame_len = len(self._packets)
|
|
||||||
self._read_offset = 0
|
|
||||||
self.is_open = True
|
|
||||||
log.info(f"Replay connection opened: {self._npy_dir} "
|
|
||||||
f"(MTI={'ON' if self._mti_enable else 'OFF'}, "
|
|
||||||
f"{self._frame_len} bytes/frame)")
|
|
||||||
return True
|
|
||||||
except (OSError, ValueError, IndexError, struct.error) as e:
|
|
||||||
log.error(f"Replay open failed: {e}")
|
|
||||||
return False
|
|
||||||
|
|
||||||
def close(self):
|
|
||||||
self.is_open = False
|
|
||||||
|
|
||||||
def read(self, size: int = 4096) -> bytes | None:
|
|
||||||
if not self.is_open:
|
|
||||||
return None
|
|
||||||
# Pace reads to target FPS (spread across ~64 reads per frame)
|
|
||||||
time.sleep((1.0 / self._replay_fps) / (NUM_CELLS / 32))
|
|
||||||
with self._lock:
|
|
||||||
# If params changed, rebuild packets
|
|
||||||
if self._needs_rebuild:
|
|
||||||
self._packets = self._build_packets()
|
|
||||||
self._frame_len = len(self._packets)
|
|
||||||
self._read_offset = 0
|
|
||||||
self._needs_rebuild = False
|
|
||||||
end = self._read_offset + size
|
|
||||||
if end <= self._frame_len:
|
|
||||||
chunk = self._packets[self._read_offset:end]
|
|
||||||
self._read_offset = end
|
|
||||||
else:
|
|
||||||
chunk = self._packets[self._read_offset:]
|
|
||||||
self._read_offset = 0
|
|
||||||
return chunk
|
|
||||||
|
|
||||||
def write(self, data: bytes) -> bool:
|
|
||||||
"""
|
|
||||||
Handle host commands in replay mode.
|
|
||||||
Signal-processing params (CFAR, MTI, DC notch) trigger re-processing.
|
|
||||||
Hardware-only params are silently ignored.
|
|
||||||
"""
|
|
||||||
if len(data) < 4:
|
|
||||||
return True
|
|
||||||
word = struct.unpack(">I", data[:4])[0]
|
|
||||||
opcode = (word >> 24) & 0xFF
|
|
||||||
value = word & 0xFFFF
|
|
||||||
|
|
||||||
if opcode in _REPLAY_ADJUSTABLE_OPCODES:
|
|
||||||
changed = False
|
|
||||||
with self._lock:
|
|
||||||
if opcode == 0x03: # DETECT_THRESHOLD
|
|
||||||
if self._detect_threshold != value:
|
|
||||||
self._detect_threshold = value
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x21: # CFAR_GUARD
|
|
||||||
if self._cfar_guard != value:
|
|
||||||
self._cfar_guard = value
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x22: # CFAR_TRAIN
|
|
||||||
if self._cfar_train != value:
|
|
||||||
self._cfar_train = value
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x23: # CFAR_ALPHA
|
|
||||||
if self._cfar_alpha != value:
|
|
||||||
self._cfar_alpha = value
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x24: # CFAR_MODE
|
|
||||||
if self._cfar_mode != value:
|
|
||||||
self._cfar_mode = value
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x25: # CFAR_ENABLE
|
|
||||||
new_en = bool(value)
|
|
||||||
if self._cfar_enable != new_en:
|
|
||||||
self._cfar_enable = new_en
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x26: # MTI_ENABLE
|
|
||||||
new_en = bool(value)
|
|
||||||
if self._mti_enable != new_en:
|
|
||||||
self._mti_enable = new_en
|
|
||||||
changed = True
|
|
||||||
elif opcode == 0x27 and self._dc_notch_width != value: # DC_NOTCH_WIDTH
|
|
||||||
self._dc_notch_width = value
|
|
||||||
changed = True
|
|
||||||
if changed:
|
|
||||||
self._needs_rebuild = True
|
|
||||||
if changed:
|
|
||||||
log.info(f"Replay param updated: opcode=0x{opcode:02X} "
|
|
||||||
f"value={value} — will re-process")
|
|
||||||
else:
|
|
||||||
log.debug(f"Replay param unchanged: opcode=0x{opcode:02X} "
|
|
||||||
f"value={value}")
|
|
||||||
elif opcode in _HARDWARE_ONLY_OPCODES:
|
|
||||||
log.debug(f"Replay: hardware-only opcode 0x{opcode:02X} "
|
|
||||||
f"(ignored in replay mode)")
|
|
||||||
else:
|
|
||||||
log.debug(f"Replay: unknown opcode 0x{opcode:02X} (ignored)")
|
|
||||||
return True
|
|
||||||
|
|
||||||
def _load_arrays(self):
|
|
||||||
"""Load source npy arrays once."""
|
|
||||||
npy = self._npy_dir
|
|
||||||
# MTI Doppler
|
|
||||||
self._dop_mti_i = np.load(
|
|
||||||
os.path.join(npy, "fullchain_mti_doppler_i.npy")).astype(np.int64)
|
|
||||||
self._dop_mti_q = np.load(
|
|
||||||
os.path.join(npy, "fullchain_mti_doppler_q.npy")).astype(np.int64)
|
|
||||||
# Non-MTI Doppler
|
|
||||||
self._dop_nomti_i = np.load(
|
|
||||||
os.path.join(npy, "doppler_map_i.npy")).astype(np.int64)
|
|
||||||
self._dop_nomti_q = np.load(
|
|
||||||
os.path.join(npy, "doppler_map_q.npy")).astype(np.int64)
|
|
||||||
# Range data
|
|
||||||
try:
|
|
||||||
range_i_all = np.load(
|
|
||||||
os.path.join(npy, "decimated_range_i.npy")).astype(np.int64)
|
|
||||||
range_q_all = np.load(
|
|
||||||
os.path.join(npy, "decimated_range_q.npy")).astype(np.int64)
|
|
||||||
self._range_i_vec = range_i_all[-1, :] # last chirp
|
|
||||||
self._range_q_vec = range_q_all[-1, :]
|
|
||||||
except FileNotFoundError:
|
|
||||||
self._range_i_vec = np.zeros(NUM_RANGE_BINS, dtype=np.int64)
|
|
||||||
self._range_q_vec = np.zeros(NUM_RANGE_BINS, dtype=np.int64)
|
|
||||||
|
|
||||||
def _build_packets(self) -> bytes:
|
|
||||||
"""Build a full frame of USB data packets from current params."""
|
|
||||||
# Select Doppler data based on MTI
|
|
||||||
if self._mti_enable:
|
|
||||||
dop_i = self._dop_mti_i
|
|
||||||
dop_q = self._dop_mti_q
|
|
||||||
else:
|
|
||||||
dop_i = self._dop_nomti_i
|
|
||||||
dop_q = self._dop_nomti_q
|
|
||||||
|
|
||||||
# Apply DC notch
|
|
||||||
dop_i, dop_q = _replay_dc_notch(dop_i, dop_q, self._dc_notch_width)
|
|
||||||
|
|
||||||
# Run CFAR
|
|
||||||
if self._cfar_enable:
|
|
||||||
det, _mag = _replay_cfar(
|
|
||||||
dop_i, dop_q,
|
|
||||||
guard=self._cfar_guard,
|
|
||||||
train=self._cfar_train,
|
|
||||||
alpha_q44=self._cfar_alpha,
|
|
||||||
mode=self._cfar_mode,
|
|
||||||
)
|
|
||||||
else:
|
|
||||||
# Simple threshold fallback matching RTL cfar_ca.v:
|
|
||||||
# detect = (|I| + |Q|) > detect_threshold (L1 norm)
|
|
||||||
mag = np.abs(dop_i) + np.abs(dop_q)
|
|
||||||
det = mag > self._detect_threshold
|
|
||||||
|
|
||||||
det_count = int(det.sum())
|
|
||||||
log.info(f"Replay: rebuilt {NUM_CELLS} packets ("
|
|
||||||
f"MTI={'ON' if self._mti_enable else 'OFF'}, "
|
|
||||||
f"DC_notch={self._dc_notch_width}, "
|
|
||||||
f"CFAR={'ON' if self._cfar_enable else 'OFF'} "
|
|
||||||
f"G={self._cfar_guard} T={self._cfar_train} "
|
|
||||||
f"a=0x{self._cfar_alpha:02X} m={self._cfar_mode}, "
|
|
||||||
f"{det_count} detections)")
|
|
||||||
|
|
||||||
range_i = self._range_i_vec
|
|
||||||
range_q = self._range_q_vec
|
|
||||||
|
|
||||||
return self._build_packets_data(range_i, range_q, dop_i, dop_q, det)
|
|
||||||
|
|
||||||
def _build_packets_data(self, range_i, range_q, dop_i, dop_q, det) -> bytes:
|
|
||||||
"""Build 11-byte data packets for FT2232H interface."""
|
|
||||||
buf = bytearray(NUM_CELLS * DATA_PACKET_SIZE)
|
|
||||||
pos = 0
|
|
||||||
for rbin in range(NUM_RANGE_BINS):
|
|
||||||
ri = int(np.clip(range_i[rbin], -32768, 32767))
|
|
||||||
rq = int(np.clip(range_q[rbin], -32768, 32767))
|
|
||||||
rq_bytes = struct.pack(">h", rq)
|
|
||||||
ri_bytes = struct.pack(">h", ri)
|
|
||||||
for dbin in range(NUM_DOPPLER_BINS):
|
|
||||||
di = int(np.clip(dop_i[rbin, dbin], -32768, 32767))
|
|
||||||
dq = int(np.clip(dop_q[rbin, dbin], -32768, 32767))
|
|
||||||
d = 1 if det[rbin, dbin] else 0
|
|
||||||
|
|
||||||
buf[pos] = HEADER_BYTE
|
|
||||||
pos += 1
|
|
||||||
buf[pos:pos+2] = rq_bytes
|
|
||||||
pos += 2
|
|
||||||
buf[pos:pos+2] = ri_bytes
|
|
||||||
pos += 2
|
|
||||||
buf[pos:pos+2] = struct.pack(">h", di)
|
|
||||||
pos += 2
|
|
||||||
buf[pos:pos+2] = struct.pack(">h", dq)
|
|
||||||
pos += 2
|
|
||||||
buf[pos] = d
|
|
||||||
pos += 1
|
|
||||||
buf[pos] = FOOTER_BYTE
|
|
||||||
pos += 1
|
|
||||||
|
|
||||||
return bytes(buf)
|
|
||||||
|
|
||||||
|
|
||||||
# ============================================================================
|
# ============================================================================
|
||||||
|
|||||||
+198
-230
@@ -3,8 +3,8 @@
|
|||||||
Tests for AERIS-10 Radar Dashboard protocol parsing, command building,
|
Tests for AERIS-10 Radar Dashboard protocol parsing, command building,
|
||||||
data recording, and acquisition logic.
|
data recording, and acquisition logic.
|
||||||
|
|
||||||
Run: python -m pytest test_radar_dashboard.py -v
|
Run: python -m pytest test_GUI_V65_Tk.py -v
|
||||||
or: python test_radar_dashboard.py
|
or: python test_GUI_V65_Tk.py
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import struct
|
import struct
|
||||||
@@ -19,10 +19,10 @@ from radar_protocol import (
|
|||||||
RadarProtocol, FT2232HConnection, DataRecorder, RadarAcquisition,
|
RadarProtocol, FT2232HConnection, DataRecorder, RadarAcquisition,
|
||||||
RadarFrame, StatusResponse, Opcode,
|
RadarFrame, StatusResponse, Opcode,
|
||||||
HEADER_BYTE, FOOTER_BYTE, STATUS_HEADER_BYTE,
|
HEADER_BYTE, FOOTER_BYTE, STATUS_HEADER_BYTE,
|
||||||
NUM_RANGE_BINS, NUM_DOPPLER_BINS, NUM_CELLS,
|
NUM_RANGE_BINS, NUM_DOPPLER_BINS,
|
||||||
DATA_PACKET_SIZE,
|
DATA_PACKET_SIZE,
|
||||||
_HARDWARE_ONLY_OPCODES,
|
|
||||||
)
|
)
|
||||||
|
from GUI_V65_Tk import DemoTarget, DemoSimulator, _ReplayController
|
||||||
|
|
||||||
|
|
||||||
class TestRadarProtocol(unittest.TestCase):
|
class TestRadarProtocol(unittest.TestCase):
|
||||||
@@ -459,218 +459,6 @@ class TestEndToEnd(unittest.TestCase):
|
|||||||
self.assertEqual(result["detection"], 1)
|
self.assertEqual(result["detection"], 1)
|
||||||
|
|
||||||
|
|
||||||
class TestReplayConnection(unittest.TestCase):
|
|
||||||
"""Test ReplayConnection with real .npy data files."""
|
|
||||||
|
|
||||||
NPY_DIR = os.path.join(
|
|
||||||
os.path.dirname(__file__), "..", "9_2_FPGA", "tb", "cosim",
|
|
||||||
"real_data", "hex"
|
|
||||||
)
|
|
||||||
|
|
||||||
def _npy_available(self):
|
|
||||||
"""Check if the npy data files exist."""
|
|
||||||
return os.path.isfile(os.path.join(self.NPY_DIR,
|
|
||||||
"fullchain_mti_doppler_i.npy"))
|
|
||||||
|
|
||||||
def test_replay_open_close(self):
|
|
||||||
"""ReplayConnection opens and closes without error."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
self.assertTrue(conn.open())
|
|
||||||
self.assertTrue(conn.is_open)
|
|
||||||
conn.close()
|
|
||||||
self.assertFalse(conn.is_open)
|
|
||||||
|
|
||||||
def test_replay_packet_count(self):
|
|
||||||
"""Replay builds exactly NUM_CELLS (2048) packets."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# Each packet is 11 bytes, total = 2048 * 11
|
|
||||||
expected_bytes = NUM_CELLS * DATA_PACKET_SIZE
|
|
||||||
self.assertEqual(conn._frame_len, expected_bytes)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_packets_parseable(self):
|
|
||||||
"""Every packet from replay can be parsed by RadarProtocol."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
raw = conn._packets
|
|
||||||
boundaries = RadarProtocol.find_packet_boundaries(raw)
|
|
||||||
self.assertEqual(len(boundaries), NUM_CELLS)
|
|
||||||
parsed_count = 0
|
|
||||||
det_count = 0
|
|
||||||
for start, end, ptype in boundaries:
|
|
||||||
self.assertEqual(ptype, "data")
|
|
||||||
result = RadarProtocol.parse_data_packet(raw[start:end])
|
|
||||||
self.assertIsNotNone(result)
|
|
||||||
parsed_count += 1
|
|
||||||
if result["detection"]:
|
|
||||||
det_count += 1
|
|
||||||
self.assertEqual(parsed_count, NUM_CELLS)
|
|
||||||
# Default: MTI=ON, DC_notch=2, CFAR CA g=2 t=8 a=0x30 → 4 detections
|
|
||||||
self.assertEqual(det_count, 4)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_read_loops(self):
|
|
||||||
"""Read returns data and loops back around."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True, replay_fps=1000)
|
|
||||||
conn.open()
|
|
||||||
total_read = 0
|
|
||||||
for _ in range(100):
|
|
||||||
chunk = conn.read(1024)
|
|
||||||
self.assertIsNotNone(chunk)
|
|
||||||
total_read += len(chunk)
|
|
||||||
self.assertGreater(total_read, 0)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_no_mti(self):
|
|
||||||
"""ReplayConnection works with use_mti=False (CFAR still runs)."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=False)
|
|
||||||
conn.open()
|
|
||||||
self.assertEqual(conn._frame_len, NUM_CELLS * DATA_PACKET_SIZE)
|
|
||||||
# No-MTI with DC notch=2 and default CFAR → 0 detections
|
|
||||||
raw = conn._packets
|
|
||||||
boundaries = RadarProtocol.find_packet_boundaries(raw)
|
|
||||||
det_count = sum(1 for s, e, t in boundaries
|
|
||||||
if RadarProtocol.parse_data_packet(raw[s:e]).get("detection", 0))
|
|
||||||
self.assertEqual(det_count, 0)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_write_returns_true(self):
|
|
||||||
"""Write on replay connection returns True."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR)
|
|
||||||
conn.open()
|
|
||||||
self.assertTrue(conn.write(b"\x01\x00\x00\x01"))
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_adjustable_param_cfar_guard(self):
|
|
||||||
"""Changing CFAR guard via write() triggers re-processing."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# Initial: guard=2 → 4 detections
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
# Send CFAR_GUARD=4
|
|
||||||
cmd = RadarProtocol.build_command(0x21, 4)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertTrue(conn._needs_rebuild)
|
|
||||||
self.assertEqual(conn._cfar_guard, 4)
|
|
||||||
# Read triggers rebuild
|
|
||||||
conn.read(1024)
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_adjustable_param_mti_toggle(self):
|
|
||||||
"""Toggling MTI via write() triggers re-processing."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# Disable MTI
|
|
||||||
cmd = RadarProtocol.build_command(0x26, 0)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertTrue(conn._needs_rebuild)
|
|
||||||
self.assertFalse(conn._mti_enable)
|
|
||||||
# Read to trigger rebuild, then count detections
|
|
||||||
# Drain all packets after rebuild
|
|
||||||
conn.read(1024) # triggers rebuild
|
|
||||||
raw = conn._packets
|
|
||||||
boundaries = RadarProtocol.find_packet_boundaries(raw)
|
|
||||||
det_count = sum(1 for s, e, t in boundaries
|
|
||||||
if RadarProtocol.parse_data_packet(raw[s:e]).get("detection", 0))
|
|
||||||
# No-MTI with default CFAR → 0 detections
|
|
||||||
self.assertEqual(det_count, 0)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_adjustable_param_dc_notch(self):
|
|
||||||
"""Changing DC notch width via write() triggers re-processing."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# Change DC notch to 0 (no notch)
|
|
||||||
cmd = RadarProtocol.build_command(0x27, 0)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertTrue(conn._needs_rebuild)
|
|
||||||
self.assertEqual(conn._dc_notch_width, 0)
|
|
||||||
conn.read(1024) # triggers rebuild
|
|
||||||
raw = conn._packets
|
|
||||||
boundaries = RadarProtocol.find_packet_boundaries(raw)
|
|
||||||
det_count = sum(1 for s, e, t in boundaries
|
|
||||||
if RadarProtocol.parse_data_packet(raw[s:e]).get("detection", 0))
|
|
||||||
# DC notch=0 with MTI → 6 detections (more noise passes through)
|
|
||||||
self.assertEqual(det_count, 6)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_hardware_opcode_ignored(self):
|
|
||||||
"""Hardware-only opcodes don't trigger rebuild."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# Send TRIGGER (hardware-only)
|
|
||||||
cmd = RadarProtocol.build_command(0x01, 1)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
# Send STREAM_CONTROL (hardware-only, opcode 0x04)
|
|
||||||
cmd = RadarProtocol.build_command(0x04, 7)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_same_value_no_rebuild(self):
|
|
||||||
"""Setting same value as current doesn't trigger rebuild."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# CFAR guard already 2
|
|
||||||
cmd = RadarProtocol.build_command(0x21, 2)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
def test_replay_self_test_opcodes_are_hardware_only(self):
|
|
||||||
"""Self-test opcodes 0x30/0x31 are hardware-only (ignored in replay)."""
|
|
||||||
if not self._npy_available():
|
|
||||||
self.skipTest("npy data files not found")
|
|
||||||
from radar_protocol import ReplayConnection
|
|
||||||
conn = ReplayConnection(self.NPY_DIR, use_mti=True)
|
|
||||||
conn.open()
|
|
||||||
# Send self-test trigger
|
|
||||||
cmd = RadarProtocol.build_command(0x30, 1)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
# Send self-test status request
|
|
||||||
cmd = RadarProtocol.build_command(0x31, 0)
|
|
||||||
conn.write(cmd)
|
|
||||||
self.assertFalse(conn._needs_rebuild)
|
|
||||||
conn.close()
|
|
||||||
|
|
||||||
|
|
||||||
class TestOpcodeEnum(unittest.TestCase):
|
class TestOpcodeEnum(unittest.TestCase):
|
||||||
"""Verify Opcode enum matches RTL host register map (radar_system_top.v)."""
|
"""Verify Opcode enum matches RTL host register map (radar_system_top.v)."""
|
||||||
|
|
||||||
@@ -690,15 +478,6 @@ class TestOpcodeEnum(unittest.TestCase):
|
|||||||
"""SELF_TEST_STATUS opcode must be 0x31."""
|
"""SELF_TEST_STATUS opcode must be 0x31."""
|
||||||
self.assertEqual(Opcode.SELF_TEST_STATUS, 0x31)
|
self.assertEqual(Opcode.SELF_TEST_STATUS, 0x31)
|
||||||
|
|
||||||
def test_self_test_in_hardware_only(self):
|
|
||||||
"""Self-test opcodes must be in _HARDWARE_ONLY_OPCODES."""
|
|
||||||
self.assertIn(0x30, _HARDWARE_ONLY_OPCODES)
|
|
||||||
self.assertIn(0x31, _HARDWARE_ONLY_OPCODES)
|
|
||||||
|
|
||||||
def test_0x16_in_hardware_only(self):
|
|
||||||
"""GAIN_SHIFT 0x16 must be in _HARDWARE_ONLY_OPCODES."""
|
|
||||||
self.assertIn(0x16, _HARDWARE_ONLY_OPCODES)
|
|
||||||
|
|
||||||
def test_stream_control_is_0x04(self):
|
def test_stream_control_is_0x04(self):
|
||||||
"""STREAM_CONTROL must be 0x04 (matches radar_system_top.v:906)."""
|
"""STREAM_CONTROL must be 0x04 (matches radar_system_top.v:906)."""
|
||||||
self.assertEqual(Opcode.STREAM_CONTROL, 0x04)
|
self.assertEqual(Opcode.STREAM_CONTROL, 0x04)
|
||||||
@@ -717,11 +496,6 @@ class TestOpcodeEnum(unittest.TestCase):
|
|||||||
self.assertEqual(Opcode.DETECT_THRESHOLD, 0x03)
|
self.assertEqual(Opcode.DETECT_THRESHOLD, 0x03)
|
||||||
self.assertEqual(Opcode.STREAM_CONTROL, 0x04)
|
self.assertEqual(Opcode.STREAM_CONTROL, 0x04)
|
||||||
|
|
||||||
def test_stale_opcodes_not_in_hardware_only(self):
|
|
||||||
"""Old wrong opcode values must not be in _HARDWARE_ONLY_OPCODES."""
|
|
||||||
self.assertNotIn(0x05, _HARDWARE_ONLY_OPCODES) # was wrong STREAM_ENABLE
|
|
||||||
self.assertNotIn(0x06, _HARDWARE_ONLY_OPCODES) # was wrong GAIN_SHIFT
|
|
||||||
|
|
||||||
def test_all_rtl_opcodes_present(self):
|
def test_all_rtl_opcodes_present(self):
|
||||||
"""Every RTL opcode (from radar_system_top.v) has a matching Opcode enum member."""
|
"""Every RTL opcode (from radar_system_top.v) has a matching Opcode enum member."""
|
||||||
expected = {0x01, 0x02, 0x03, 0x04,
|
expected = {0x01, 0x02, 0x03, 0x04,
|
||||||
@@ -946,5 +720,199 @@ class TestAGCVisualizationHistory(unittest.TestCase):
|
|||||||
self.assertAlmostEqual(max(200 * 1.5, 5), 300.0)
|
self.assertAlmostEqual(max(200 * 1.5, 5), 300.0)
|
||||||
|
|
||||||
|
|
||||||
|
# =====================================================================
|
||||||
|
# Tests for DemoTarget, DemoSimulator, and _ReplayController
|
||||||
|
# =====================================================================
|
||||||
|
|
||||||
|
|
||||||
|
class TestDemoTarget(unittest.TestCase):
|
||||||
|
"""Unit tests for DemoTarget kinematics."""
|
||||||
|
|
||||||
|
def test_initial_values_in_range(self):
|
||||||
|
t = DemoTarget(1)
|
||||||
|
self.assertEqual(t.id, 1)
|
||||||
|
self.assertGreaterEqual(t.range_m, 20)
|
||||||
|
self.assertLessEqual(t.range_m, DemoTarget._MAX_RANGE)
|
||||||
|
self.assertIn(t.classification, ["aircraft", "drone", "bird", "unknown"])
|
||||||
|
|
||||||
|
def test_step_returns_true_in_normal_range(self):
|
||||||
|
t = DemoTarget(2)
|
||||||
|
t.range_m = 150.0
|
||||||
|
t.velocity = 0.0
|
||||||
|
self.assertTrue(t.step())
|
||||||
|
|
||||||
|
def test_step_returns_false_when_out_of_range_high(self):
|
||||||
|
t = DemoTarget(3)
|
||||||
|
t.range_m = DemoTarget._MAX_RANGE + 1
|
||||||
|
t.velocity = -1.0 # moving away
|
||||||
|
self.assertFalse(t.step())
|
||||||
|
|
||||||
|
def test_step_returns_false_when_out_of_range_low(self):
|
||||||
|
t = DemoTarget(4)
|
||||||
|
t.range_m = 2.0
|
||||||
|
t.velocity = 1.0 # moving closer
|
||||||
|
self.assertFalse(t.step())
|
||||||
|
|
||||||
|
def test_velocity_clamped(self):
|
||||||
|
t = DemoTarget(5)
|
||||||
|
t.velocity = 19.0
|
||||||
|
t.range_m = 150.0
|
||||||
|
# Step many times — velocity should stay within [-20, 20]
|
||||||
|
for _ in range(100):
|
||||||
|
t.range_m = 150.0 # keep in range
|
||||||
|
t.step()
|
||||||
|
self.assertGreaterEqual(t.velocity, -20)
|
||||||
|
self.assertLessEqual(t.velocity, 20)
|
||||||
|
|
||||||
|
def test_snr_clamped(self):
|
||||||
|
t = DemoTarget(6)
|
||||||
|
t.snr = 49.5
|
||||||
|
t.range_m = 150.0
|
||||||
|
for _ in range(100):
|
||||||
|
t.range_m = 150.0
|
||||||
|
t.step()
|
||||||
|
self.assertGreaterEqual(t.snr, 0)
|
||||||
|
self.assertLessEqual(t.snr, 50)
|
||||||
|
|
||||||
|
|
||||||
|
class TestDemoSimulatorNoTk(unittest.TestCase):
|
||||||
|
"""Test DemoSimulator logic without a real Tk event loop.
|
||||||
|
|
||||||
|
We replace ``root.after`` with a mock to avoid needing a display.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def _make_simulator(self):
|
||||||
|
from unittest.mock import MagicMock
|
||||||
|
|
||||||
|
fq = queue.Queue(maxsize=100)
|
||||||
|
uq = queue.Queue(maxsize=100)
|
||||||
|
mock_root = MagicMock()
|
||||||
|
# root.after(ms, fn) should return an id (str)
|
||||||
|
mock_root.after.return_value = "mock_after_id"
|
||||||
|
sim = DemoSimulator(fq, uq, mock_root, interval_ms=100)
|
||||||
|
return sim, fq, uq, mock_root
|
||||||
|
|
||||||
|
def test_initial_targets_created(self):
|
||||||
|
sim, _fq, _uq, _root = self._make_simulator()
|
||||||
|
# Should seed 8 initial targets
|
||||||
|
self.assertEqual(len(sim._targets), 8)
|
||||||
|
|
||||||
|
def test_tick_produces_frame_and_targets(self):
|
||||||
|
sim, fq, uq, _root = self._make_simulator()
|
||||||
|
sim._tick()
|
||||||
|
# Should have a frame
|
||||||
|
self.assertFalse(fq.empty())
|
||||||
|
frame = fq.get_nowait()
|
||||||
|
self.assertIsInstance(frame, RadarFrame)
|
||||||
|
self.assertEqual(frame.frame_number, 1)
|
||||||
|
# Should have demo_targets in ui_queue
|
||||||
|
tag, payload = uq.get_nowait()
|
||||||
|
self.assertEqual(tag, "demo_targets")
|
||||||
|
self.assertIsInstance(payload, list)
|
||||||
|
|
||||||
|
def test_tick_produces_nonzero_detections(self):
|
||||||
|
"""Demo targets should actually render into the range-Doppler grid."""
|
||||||
|
sim, fq, _uq, _root = self._make_simulator()
|
||||||
|
sim._tick()
|
||||||
|
frame = fq.get_nowait()
|
||||||
|
# At least some targets should produce magnitude > 0 and detections
|
||||||
|
self.assertGreater(frame.magnitude.sum(), 0,
|
||||||
|
"Demo targets should render into range-Doppler grid")
|
||||||
|
self.assertGreater(frame.detection_count, 0,
|
||||||
|
"Demo targets should produce detections")
|
||||||
|
|
||||||
|
def test_stop_cancels_after(self):
|
||||||
|
sim, _fq, _uq, mock_root = self._make_simulator()
|
||||||
|
sim._tick() # sets _after_id
|
||||||
|
sim.stop()
|
||||||
|
mock_root.after_cancel.assert_called_once_with("mock_after_id")
|
||||||
|
self.assertIsNone(sim._after_id)
|
||||||
|
|
||||||
|
|
||||||
|
class TestReplayController(unittest.TestCase):
|
||||||
|
"""Unit tests for _ReplayController (no GUI required)."""
|
||||||
|
|
||||||
|
def test_initial_state(self):
|
||||||
|
fq = queue.Queue()
|
||||||
|
uq = queue.Queue()
|
||||||
|
ctrl = _ReplayController(fq, uq)
|
||||||
|
self.assertEqual(ctrl.total_frames, 0)
|
||||||
|
self.assertEqual(ctrl.current_index, 0)
|
||||||
|
self.assertFalse(ctrl.is_playing)
|
||||||
|
self.assertIsNone(ctrl.software_fpga)
|
||||||
|
|
||||||
|
def test_set_speed(self):
|
||||||
|
ctrl = _ReplayController(queue.Queue(), queue.Queue())
|
||||||
|
ctrl.set_speed("2x")
|
||||||
|
self.assertAlmostEqual(ctrl._frame_interval, 0.050)
|
||||||
|
|
||||||
|
def test_set_speed_unknown_falls_back(self):
|
||||||
|
ctrl = _ReplayController(queue.Queue(), queue.Queue())
|
||||||
|
ctrl.set_speed("99x")
|
||||||
|
self.assertAlmostEqual(ctrl._frame_interval, 0.100)
|
||||||
|
|
||||||
|
def test_set_loop(self):
|
||||||
|
ctrl = _ReplayController(queue.Queue(), queue.Queue())
|
||||||
|
ctrl.set_loop(True)
|
||||||
|
self.assertTrue(ctrl._loop)
|
||||||
|
ctrl.set_loop(False)
|
||||||
|
self.assertFalse(ctrl._loop)
|
||||||
|
|
||||||
|
def test_seek_increments_past_emitted(self):
|
||||||
|
"""After seek(), _current_index should be one past the seeked frame."""
|
||||||
|
fq = queue.Queue(maxsize=100)
|
||||||
|
uq = queue.Queue(maxsize=100)
|
||||||
|
ctrl = _ReplayController(fq, uq)
|
||||||
|
# Manually set engine to a mock to allow seek
|
||||||
|
from unittest.mock import MagicMock
|
||||||
|
mock_engine = MagicMock()
|
||||||
|
mock_engine.total_frames = 10
|
||||||
|
mock_engine.get_frame.return_value = RadarFrame()
|
||||||
|
ctrl._engine = mock_engine
|
||||||
|
ctrl.seek(5)
|
||||||
|
# _current_index should be 6 (past the emitted frame)
|
||||||
|
self.assertEqual(ctrl._current_index, 6)
|
||||||
|
self.assertEqual(ctrl._last_emitted_index, 5)
|
||||||
|
# Frame should be in the queue
|
||||||
|
self.assertFalse(fq.empty())
|
||||||
|
|
||||||
|
def test_seek_clamps_to_bounds(self):
|
||||||
|
from unittest.mock import MagicMock
|
||||||
|
|
||||||
|
fq = queue.Queue(maxsize=100)
|
||||||
|
uq = queue.Queue(maxsize=100)
|
||||||
|
ctrl = _ReplayController(fq, uq)
|
||||||
|
mock_engine = MagicMock()
|
||||||
|
mock_engine.total_frames = 5
|
||||||
|
mock_engine.get_frame.return_value = RadarFrame()
|
||||||
|
ctrl._engine = mock_engine
|
||||||
|
|
||||||
|
ctrl.seek(100)
|
||||||
|
# Should clamp to last frame (index 4), then _current_index = 5
|
||||||
|
self.assertEqual(ctrl._last_emitted_index, 4)
|
||||||
|
self.assertEqual(ctrl._current_index, 5)
|
||||||
|
|
||||||
|
ctrl.seek(-10)
|
||||||
|
# Should clamp to 0, then _current_index = 1
|
||||||
|
self.assertEqual(ctrl._last_emitted_index, 0)
|
||||||
|
self.assertEqual(ctrl._current_index, 1)
|
||||||
|
|
||||||
|
def test_close_releases_engine(self):
|
||||||
|
from unittest.mock import MagicMock
|
||||||
|
|
||||||
|
fq = queue.Queue(maxsize=100)
|
||||||
|
uq = queue.Queue(maxsize=100)
|
||||||
|
ctrl = _ReplayController(fq, uq)
|
||||||
|
mock_engine = MagicMock()
|
||||||
|
mock_engine.total_frames = 5
|
||||||
|
mock_engine.get_frame.return_value = RadarFrame()
|
||||||
|
ctrl._engine = mock_engine
|
||||||
|
|
||||||
|
ctrl.close()
|
||||||
|
mock_engine.close.assert_called_once()
|
||||||
|
self.assertIsNone(ctrl._engine)
|
||||||
|
self.assertIsNone(ctrl.software_fpga)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
unittest.main(verbosity=2)
|
unittest.main(verbosity=2)
|
||||||
@@ -11,6 +11,7 @@ Does NOT require a running Qt event loop — only unit-testable components.
|
|||||||
Run with: python -m unittest test_v7 -v
|
Run with: python -m unittest test_v7 -v
|
||||||
"""
|
"""
|
||||||
|
|
||||||
|
import os
|
||||||
import struct
|
import struct
|
||||||
import unittest
|
import unittest
|
||||||
from dataclasses import asdict
|
from dataclasses import asdict
|
||||||
@@ -264,6 +265,15 @@ class TestUSBPacketParser(unittest.TestCase):
|
|||||||
# Test: v7.workers — polar_to_geographic
|
# Test: v7.workers — polar_to_geographic
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
|
|
||||||
|
def _pyqt6_available():
|
||||||
|
try:
|
||||||
|
import PyQt6.QtCore # noqa: F401
|
||||||
|
return True
|
||||||
|
except ImportError:
|
||||||
|
return False
|
||||||
|
|
||||||
|
|
||||||
|
@unittest.skipUnless(_pyqt6_available(), "PyQt6 not installed")
|
||||||
class TestPolarToGeographic(unittest.TestCase):
|
class TestPolarToGeographic(unittest.TestCase):
|
||||||
def test_north_bearing(self):
|
def test_north_bearing(self):
|
||||||
from v7.workers import polar_to_geographic
|
from v7.workers import polar_to_geographic
|
||||||
@@ -326,12 +336,16 @@ class TestV7Init(unittest.TestCase):
|
|||||||
|
|
||||||
def test_key_exports(self):
|
def test_key_exports(self):
|
||||||
import v7
|
import v7
|
||||||
|
# Core exports (no PyQt6 required)
|
||||||
for name in ["RadarTarget", "RadarSettings", "GPSData",
|
for name in ["RadarTarget", "RadarSettings", "GPSData",
|
||||||
"ProcessingConfig", "FT2232HConnection",
|
"ProcessingConfig", "FT2232HConnection",
|
||||||
"RadarProtocol", "RadarProcessor",
|
"RadarProtocol", "RadarProcessor"]:
|
||||||
"RadarDataWorker", "RadarMapWidget",
|
|
||||||
"RadarDashboard"]:
|
|
||||||
self.assertTrue(hasattr(v7, name), f"v7 missing export: {name}")
|
self.assertTrue(hasattr(v7, name), f"v7 missing export: {name}")
|
||||||
|
# PyQt6-dependent exports — only present when PyQt6 is installed
|
||||||
|
if _pyqt6_available():
|
||||||
|
for name in ["RadarDataWorker", "RadarMapWidget",
|
||||||
|
"RadarDashboard"]:
|
||||||
|
self.assertTrue(hasattr(v7, name), f"v7 missing export: {name}")
|
||||||
|
|
||||||
|
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
@@ -401,6 +415,559 @@ class TestAGCVisualizationV7(unittest.TestCase):
|
|||||||
self.assertEqual(pick_color(11), DARK_ERROR)
|
self.assertEqual(pick_color(11), DARK_ERROR)
|
||||||
|
|
||||||
|
|
||||||
|
# =============================================================================
|
||||||
|
# Test: v7.models.WaveformConfig
|
||||||
|
# =============================================================================
|
||||||
|
|
||||||
|
class TestWaveformConfig(unittest.TestCase):
|
||||||
|
"""WaveformConfig dataclass and derived physical properties."""
|
||||||
|
|
||||||
|
def test_defaults(self):
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc = WaveformConfig()
|
||||||
|
self.assertEqual(wc.sample_rate_hz, 4e6)
|
||||||
|
self.assertEqual(wc.bandwidth_hz, 500e6)
|
||||||
|
self.assertEqual(wc.chirp_duration_s, 300e-6)
|
||||||
|
self.assertEqual(wc.center_freq_hz, 10.525e9)
|
||||||
|
self.assertEqual(wc.n_range_bins, 64)
|
||||||
|
self.assertEqual(wc.n_doppler_bins, 32)
|
||||||
|
self.assertEqual(wc.fft_size, 1024)
|
||||||
|
self.assertEqual(wc.decimation_factor, 16)
|
||||||
|
|
||||||
|
def test_range_resolution(self):
|
||||||
|
"""range_resolution_m should be ~5.62 m/bin with ADI defaults."""
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc = WaveformConfig()
|
||||||
|
self.assertAlmostEqual(wc.range_resolution_m, 5.621, places=1)
|
||||||
|
|
||||||
|
def test_velocity_resolution(self):
|
||||||
|
"""velocity_resolution_mps should be ~1.484 m/s/bin."""
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc = WaveformConfig()
|
||||||
|
self.assertAlmostEqual(wc.velocity_resolution_mps, 1.484, places=2)
|
||||||
|
|
||||||
|
def test_max_range(self):
|
||||||
|
"""max_range_m = range_resolution * n_range_bins."""
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc = WaveformConfig()
|
||||||
|
self.assertAlmostEqual(wc.max_range_m, wc.range_resolution_m * 64, places=1)
|
||||||
|
|
||||||
|
def test_max_velocity(self):
|
||||||
|
"""max_velocity_mps = velocity_resolution * n_doppler_bins / 2."""
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc = WaveformConfig()
|
||||||
|
self.assertAlmostEqual(
|
||||||
|
wc.max_velocity_mps,
|
||||||
|
wc.velocity_resolution_mps * 16,
|
||||||
|
places=2,
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_custom_params(self):
|
||||||
|
"""Non-default parameters correctly change derived values."""
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc1 = WaveformConfig()
|
||||||
|
wc2 = WaveformConfig(bandwidth_hz=1e9) # double BW → halve range res
|
||||||
|
self.assertAlmostEqual(wc2.range_resolution_m, wc1.range_resolution_m / 2, places=2)
|
||||||
|
|
||||||
|
def test_zero_center_freq_velocity(self):
|
||||||
|
"""Zero center freq should cause ZeroDivisionError in velocity calc."""
|
||||||
|
from v7.models import WaveformConfig
|
||||||
|
wc = WaveformConfig(center_freq_hz=0.0)
|
||||||
|
with self.assertRaises(ZeroDivisionError):
|
||||||
|
_ = wc.velocity_resolution_mps
|
||||||
|
|
||||||
|
|
||||||
|
# =============================================================================
|
||||||
|
# Test: v7.software_fpga.SoftwareFPGA
|
||||||
|
# =============================================================================
|
||||||
|
|
||||||
|
class TestSoftwareFPGA(unittest.TestCase):
|
||||||
|
"""SoftwareFPGA register interface and signal chain."""
|
||||||
|
|
||||||
|
def _make_fpga(self):
|
||||||
|
from v7.software_fpga import SoftwareFPGA
|
||||||
|
return SoftwareFPGA()
|
||||||
|
|
||||||
|
def test_reset_defaults(self):
|
||||||
|
"""Register reset values match FPGA RTL (radar_system_top.v)."""
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
self.assertEqual(fpga.detect_threshold, 10_000)
|
||||||
|
self.assertEqual(fpga.gain_shift, 0)
|
||||||
|
self.assertFalse(fpga.cfar_enable)
|
||||||
|
self.assertEqual(fpga.cfar_guard, 2)
|
||||||
|
self.assertEqual(fpga.cfar_train, 8)
|
||||||
|
self.assertEqual(fpga.cfar_alpha, 0x30)
|
||||||
|
self.assertEqual(fpga.cfar_mode, 0)
|
||||||
|
self.assertFalse(fpga.mti_enable)
|
||||||
|
self.assertEqual(fpga.dc_notch_width, 0)
|
||||||
|
self.assertFalse(fpga.agc_enable)
|
||||||
|
self.assertEqual(fpga.agc_target, 200)
|
||||||
|
self.assertEqual(fpga.agc_attack, 1)
|
||||||
|
self.assertEqual(fpga.agc_decay, 1)
|
||||||
|
self.assertEqual(fpga.agc_holdoff, 4)
|
||||||
|
|
||||||
|
def test_setter_detect_threshold(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_detect_threshold(5000)
|
||||||
|
self.assertEqual(fpga.detect_threshold, 5000)
|
||||||
|
|
||||||
|
def test_setter_detect_threshold_clamp_16bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_detect_threshold(0x1FFFF) # 17-bit
|
||||||
|
self.assertEqual(fpga.detect_threshold, 0xFFFF)
|
||||||
|
|
||||||
|
def test_setter_gain_shift_clamp_4bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_gain_shift(0xFF)
|
||||||
|
self.assertEqual(fpga.gain_shift, 0x0F)
|
||||||
|
|
||||||
|
def test_setter_cfar_enable(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_cfar_enable(True)
|
||||||
|
self.assertTrue(fpga.cfar_enable)
|
||||||
|
fpga.set_cfar_enable(False)
|
||||||
|
self.assertFalse(fpga.cfar_enable)
|
||||||
|
|
||||||
|
def test_setter_cfar_guard_clamp_4bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_cfar_guard(0x1F)
|
||||||
|
self.assertEqual(fpga.cfar_guard, 0x0F)
|
||||||
|
|
||||||
|
def test_setter_cfar_train_min_1(self):
|
||||||
|
"""CFAR train cells clamped to min 1."""
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_cfar_train(0)
|
||||||
|
self.assertEqual(fpga.cfar_train, 1)
|
||||||
|
|
||||||
|
def test_setter_cfar_train_clamp_5bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_cfar_train(0x3F)
|
||||||
|
self.assertEqual(fpga.cfar_train, 0x1F)
|
||||||
|
|
||||||
|
def test_setter_cfar_alpha_clamp_8bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_cfar_alpha(0x1FF)
|
||||||
|
self.assertEqual(fpga.cfar_alpha, 0xFF)
|
||||||
|
|
||||||
|
def test_setter_cfar_mode_clamp_2bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_cfar_mode(7)
|
||||||
|
self.assertEqual(fpga.cfar_mode, 3)
|
||||||
|
|
||||||
|
def test_setter_mti_enable(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_mti_enable(True)
|
||||||
|
self.assertTrue(fpga.mti_enable)
|
||||||
|
|
||||||
|
def test_setter_dc_notch_clamp_3bit(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_dc_notch_width(0xFF)
|
||||||
|
self.assertEqual(fpga.dc_notch_width, 7)
|
||||||
|
|
||||||
|
def test_setter_agc_params_selective(self):
|
||||||
|
"""set_agc_params only changes provided fields."""
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_agc_params(target=100)
|
||||||
|
self.assertEqual(fpga.agc_target, 100)
|
||||||
|
self.assertEqual(fpga.agc_attack, 1) # unchanged
|
||||||
|
fpga.set_agc_params(attack=3, decay=5)
|
||||||
|
self.assertEqual(fpga.agc_attack, 3)
|
||||||
|
self.assertEqual(fpga.agc_decay, 5)
|
||||||
|
self.assertEqual(fpga.agc_target, 100) # unchanged
|
||||||
|
|
||||||
|
def test_setter_agc_params_clamp(self):
|
||||||
|
fpga = self._make_fpga()
|
||||||
|
fpga.set_agc_params(target=0xFFF, attack=0xFF, decay=0xFF, holdoff=0xFF)
|
||||||
|
self.assertEqual(fpga.agc_target, 0xFF)
|
||||||
|
self.assertEqual(fpga.agc_attack, 0x0F)
|
||||||
|
self.assertEqual(fpga.agc_decay, 0x0F)
|
||||||
|
self.assertEqual(fpga.agc_holdoff, 0x0F)
|
||||||
|
|
||||||
|
|
||||||
|
class TestSoftwareFPGASignalChain(unittest.TestCase):
|
||||||
|
"""SoftwareFPGA.process_chirps with real co-sim data."""
|
||||||
|
|
||||||
|
COSIM_DIR = os.path.join(
|
||||||
|
os.path.dirname(__file__), "..", "9_2_FPGA", "tb", "cosim",
|
||||||
|
"real_data", "hex"
|
||||||
|
)
|
||||||
|
|
||||||
|
def _cosim_available(self):
|
||||||
|
return os.path.isfile(os.path.join(self.COSIM_DIR, "doppler_map_i.npy"))
|
||||||
|
|
||||||
|
def test_process_chirps_returns_radar_frame(self):
|
||||||
|
"""process_chirps produces a RadarFrame with correct shapes."""
|
||||||
|
if not self._cosim_available():
|
||||||
|
self.skipTest("co-sim data not found")
|
||||||
|
from v7.software_fpga import SoftwareFPGA
|
||||||
|
from radar_protocol import RadarFrame
|
||||||
|
|
||||||
|
# Load decimated range data as minimal input (32 chirps x 64 bins)
|
||||||
|
dec_i = np.load(os.path.join(self.COSIM_DIR, "decimated_range_i.npy"))
|
||||||
|
dec_q = np.load(os.path.join(self.COSIM_DIR, "decimated_range_q.npy"))
|
||||||
|
|
||||||
|
# Build fake 1024-sample chirps from decimated data (pad with zeros)
|
||||||
|
n_chirps = dec_i.shape[0]
|
||||||
|
iq_i = np.zeros((n_chirps, 1024), dtype=np.int64)
|
||||||
|
iq_q = np.zeros((n_chirps, 1024), dtype=np.int64)
|
||||||
|
# Put decimated data into first 64 bins so FFT has something
|
||||||
|
iq_i[:, :dec_i.shape[1]] = dec_i
|
||||||
|
iq_q[:, :dec_q.shape[1]] = dec_q
|
||||||
|
|
||||||
|
fpga = SoftwareFPGA()
|
||||||
|
frame = fpga.process_chirps(iq_i, iq_q, frame_number=42, timestamp=1.0)
|
||||||
|
|
||||||
|
self.assertIsInstance(frame, RadarFrame)
|
||||||
|
self.assertEqual(frame.frame_number, 42)
|
||||||
|
self.assertAlmostEqual(frame.timestamp, 1.0)
|
||||||
|
self.assertEqual(frame.range_doppler_i.shape, (64, 32))
|
||||||
|
self.assertEqual(frame.range_doppler_q.shape, (64, 32))
|
||||||
|
self.assertEqual(frame.magnitude.shape, (64, 32))
|
||||||
|
self.assertEqual(frame.detections.shape, (64, 32))
|
||||||
|
self.assertEqual(frame.range_profile.shape, (64,))
|
||||||
|
self.assertEqual(frame.detection_count, int(frame.detections.sum()))
|
||||||
|
|
||||||
|
def test_cfar_enable_changes_detections(self):
|
||||||
|
"""Enabling CFAR vs simple threshold should yield different detection counts."""
|
||||||
|
if not self._cosim_available():
|
||||||
|
self.skipTest("co-sim data not found")
|
||||||
|
from v7.software_fpga import SoftwareFPGA
|
||||||
|
|
||||||
|
iq_i = np.zeros((32, 1024), dtype=np.int64)
|
||||||
|
iq_q = np.zeros((32, 1024), dtype=np.int64)
|
||||||
|
# Inject a single strong tone in bin 10 of every chirp
|
||||||
|
iq_i[:, 10] = 5000
|
||||||
|
iq_q[:, 10] = 3000
|
||||||
|
|
||||||
|
fpga_thresh = SoftwareFPGA()
|
||||||
|
fpga_thresh.set_detect_threshold(1) # very low → many detections
|
||||||
|
frame_thresh = fpga_thresh.process_chirps(iq_i, iq_q)
|
||||||
|
|
||||||
|
fpga_cfar = SoftwareFPGA()
|
||||||
|
fpga_cfar.set_cfar_enable(True)
|
||||||
|
fpga_cfar.set_cfar_alpha(0x10) # low alpha → more detections
|
||||||
|
frame_cfar = fpga_cfar.process_chirps(iq_i, iq_q)
|
||||||
|
|
||||||
|
# Just verify both produce valid frames — exact counts depend on chain
|
||||||
|
self.assertIsNotNone(frame_thresh)
|
||||||
|
self.assertIsNotNone(frame_cfar)
|
||||||
|
self.assertEqual(frame_thresh.magnitude.shape, (64, 32))
|
||||||
|
self.assertEqual(frame_cfar.magnitude.shape, (64, 32))
|
||||||
|
|
||||||
|
|
||||||
|
class TestQuantizeRawIQ(unittest.TestCase):
|
||||||
|
"""quantize_raw_iq utility function."""
|
||||||
|
|
||||||
|
def test_3d_input(self):
|
||||||
|
"""3-D (frames, chirps, samples) → uses first frame."""
|
||||||
|
from v7.software_fpga import quantize_raw_iq
|
||||||
|
raw = np.random.randn(5, 32, 1024) + 1j * np.random.randn(5, 32, 1024)
|
||||||
|
iq_i, iq_q = quantize_raw_iq(raw)
|
||||||
|
self.assertEqual(iq_i.shape, (32, 1024))
|
||||||
|
self.assertEqual(iq_q.shape, (32, 1024))
|
||||||
|
self.assertTrue(np.all(np.abs(iq_i) <= 32767))
|
||||||
|
self.assertTrue(np.all(np.abs(iq_q) <= 32767))
|
||||||
|
|
||||||
|
def test_2d_input(self):
|
||||||
|
"""2-D (chirps, samples) → works directly."""
|
||||||
|
from v7.software_fpga import quantize_raw_iq
|
||||||
|
raw = np.random.randn(32, 1024) + 1j * np.random.randn(32, 1024)
|
||||||
|
iq_i, _iq_q = quantize_raw_iq(raw)
|
||||||
|
self.assertEqual(iq_i.shape, (32, 1024))
|
||||||
|
|
||||||
|
def test_zero_input(self):
|
||||||
|
"""All-zero complex input → all-zero output."""
|
||||||
|
from v7.software_fpga import quantize_raw_iq
|
||||||
|
raw = np.zeros((32, 1024), dtype=np.complex128)
|
||||||
|
iq_i, iq_q = quantize_raw_iq(raw)
|
||||||
|
self.assertTrue(np.all(iq_i == 0))
|
||||||
|
self.assertTrue(np.all(iq_q == 0))
|
||||||
|
|
||||||
|
def test_peak_target_scaling(self):
|
||||||
|
"""Peak of output should be near peak_target."""
|
||||||
|
from v7.software_fpga import quantize_raw_iq
|
||||||
|
raw = np.zeros((32, 1024), dtype=np.complex128)
|
||||||
|
raw[0, 0] = 1.0 + 0j # single peak
|
||||||
|
iq_i, _iq_q = quantize_raw_iq(raw, peak_target=500)
|
||||||
|
# The peak I value should be exactly 500 (sole max)
|
||||||
|
self.assertEqual(int(iq_i[0, 0]), 500)
|
||||||
|
|
||||||
|
|
||||||
|
# =============================================================================
|
||||||
|
# Test: v7.replay (ReplayEngine, detect_format)
|
||||||
|
# =============================================================================
|
||||||
|
|
||||||
|
class TestDetectFormat(unittest.TestCase):
|
||||||
|
"""detect_format auto-detection logic."""
|
||||||
|
|
||||||
|
COSIM_DIR = os.path.join(
|
||||||
|
os.path.dirname(__file__), "..", "9_2_FPGA", "tb", "cosim",
|
||||||
|
"real_data", "hex"
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_cosim_dir(self):
|
||||||
|
if not os.path.isdir(self.COSIM_DIR):
|
||||||
|
self.skipTest("co-sim dir not found")
|
||||||
|
from v7.replay import detect_format, ReplayFormat
|
||||||
|
self.assertEqual(detect_format(self.COSIM_DIR), ReplayFormat.COSIM_DIR)
|
||||||
|
|
||||||
|
def test_npy_file(self):
|
||||||
|
"""A .npy file → RAW_IQ_NPY."""
|
||||||
|
from v7.replay import detect_format, ReplayFormat
|
||||||
|
import tempfile
|
||||||
|
with tempfile.NamedTemporaryFile(suffix=".npy", delete=False) as f:
|
||||||
|
np.save(f, np.zeros((2, 32, 1024), dtype=np.complex128))
|
||||||
|
tmp = f.name
|
||||||
|
try:
|
||||||
|
self.assertEqual(detect_format(tmp), ReplayFormat.RAW_IQ_NPY)
|
||||||
|
finally:
|
||||||
|
os.unlink(tmp)
|
||||||
|
|
||||||
|
def test_h5_file(self):
|
||||||
|
"""A .h5 file → HDF5."""
|
||||||
|
from v7.replay import detect_format, ReplayFormat
|
||||||
|
self.assertEqual(detect_format("/tmp/fake_recording.h5"), ReplayFormat.HDF5)
|
||||||
|
|
||||||
|
def test_unknown_extension_raises(self):
|
||||||
|
from v7.replay import detect_format
|
||||||
|
with self.assertRaises(ValueError):
|
||||||
|
detect_format("/tmp/data.csv")
|
||||||
|
|
||||||
|
def test_empty_dir_raises(self):
|
||||||
|
"""Directory without co-sim files → ValueError."""
|
||||||
|
from v7.replay import detect_format
|
||||||
|
import tempfile
|
||||||
|
with tempfile.TemporaryDirectory() as td, self.assertRaises(ValueError):
|
||||||
|
detect_format(td)
|
||||||
|
|
||||||
|
|
||||||
|
class TestReplayEngineCosim(unittest.TestCase):
|
||||||
|
"""ReplayEngine loading from FPGA co-sim directory."""
|
||||||
|
|
||||||
|
COSIM_DIR = os.path.join(
|
||||||
|
os.path.dirname(__file__), "..", "9_2_FPGA", "tb", "cosim",
|
||||||
|
"real_data", "hex"
|
||||||
|
)
|
||||||
|
|
||||||
|
def _available(self):
|
||||||
|
return os.path.isfile(os.path.join(self.COSIM_DIR, "doppler_map_i.npy"))
|
||||||
|
|
||||||
|
def test_load_cosim(self):
|
||||||
|
if not self._available():
|
||||||
|
self.skipTest("co-sim data not found")
|
||||||
|
from v7.replay import ReplayEngine, ReplayFormat
|
||||||
|
engine = ReplayEngine(self.COSIM_DIR)
|
||||||
|
self.assertEqual(engine.fmt, ReplayFormat.COSIM_DIR)
|
||||||
|
self.assertEqual(engine.total_frames, 1)
|
||||||
|
|
||||||
|
def test_get_frame_cosim(self):
|
||||||
|
if not self._available():
|
||||||
|
self.skipTest("co-sim data not found")
|
||||||
|
from v7.replay import ReplayEngine
|
||||||
|
from radar_protocol import RadarFrame
|
||||||
|
engine = ReplayEngine(self.COSIM_DIR)
|
||||||
|
frame = engine.get_frame(0)
|
||||||
|
self.assertIsInstance(frame, RadarFrame)
|
||||||
|
self.assertEqual(frame.range_doppler_i.shape, (64, 32))
|
||||||
|
self.assertEqual(frame.magnitude.shape, (64, 32))
|
||||||
|
|
||||||
|
def test_get_frame_out_of_range(self):
|
||||||
|
if not self._available():
|
||||||
|
self.skipTest("co-sim data not found")
|
||||||
|
from v7.replay import ReplayEngine
|
||||||
|
engine = ReplayEngine(self.COSIM_DIR)
|
||||||
|
with self.assertRaises(IndexError):
|
||||||
|
engine.get_frame(1)
|
||||||
|
with self.assertRaises(IndexError):
|
||||||
|
engine.get_frame(-1)
|
||||||
|
|
||||||
|
|
||||||
|
class TestReplayEngineRawIQ(unittest.TestCase):
|
||||||
|
"""ReplayEngine loading from raw IQ .npy cube."""
|
||||||
|
|
||||||
|
def test_load_raw_iq_synthetic(self):
|
||||||
|
"""Synthetic raw IQ cube loads and produces correct frame count."""
|
||||||
|
import tempfile
|
||||||
|
from v7.replay import ReplayEngine, ReplayFormat
|
||||||
|
from v7.software_fpga import SoftwareFPGA
|
||||||
|
|
||||||
|
raw = np.random.randn(3, 32, 1024) + 1j * np.random.randn(3, 32, 1024)
|
||||||
|
with tempfile.NamedTemporaryFile(suffix=".npy", delete=False) as f:
|
||||||
|
np.save(f, raw)
|
||||||
|
tmp = f.name
|
||||||
|
try:
|
||||||
|
fpga = SoftwareFPGA()
|
||||||
|
engine = ReplayEngine(tmp, software_fpga=fpga)
|
||||||
|
self.assertEqual(engine.fmt, ReplayFormat.RAW_IQ_NPY)
|
||||||
|
self.assertEqual(engine.total_frames, 3)
|
||||||
|
finally:
|
||||||
|
os.unlink(tmp)
|
||||||
|
|
||||||
|
def test_get_frame_raw_iq_synthetic(self):
|
||||||
|
"""get_frame on raw IQ runs SoftwareFPGA and returns RadarFrame."""
|
||||||
|
import tempfile
|
||||||
|
from v7.replay import ReplayEngine
|
||||||
|
from v7.software_fpga import SoftwareFPGA
|
||||||
|
from radar_protocol import RadarFrame
|
||||||
|
|
||||||
|
raw = np.random.randn(2, 32, 1024) + 1j * np.random.randn(2, 32, 1024)
|
||||||
|
with tempfile.NamedTemporaryFile(suffix=".npy", delete=False) as f:
|
||||||
|
np.save(f, raw)
|
||||||
|
tmp = f.name
|
||||||
|
try:
|
||||||
|
fpga = SoftwareFPGA()
|
||||||
|
engine = ReplayEngine(tmp, software_fpga=fpga)
|
||||||
|
frame = engine.get_frame(0)
|
||||||
|
self.assertIsInstance(frame, RadarFrame)
|
||||||
|
self.assertEqual(frame.range_doppler_i.shape, (64, 32))
|
||||||
|
self.assertEqual(frame.frame_number, 0)
|
||||||
|
finally:
|
||||||
|
os.unlink(tmp)
|
||||||
|
|
||||||
|
def test_raw_iq_no_fpga_raises(self):
|
||||||
|
"""Raw IQ get_frame without SoftwareFPGA → RuntimeError."""
|
||||||
|
import tempfile
|
||||||
|
from v7.replay import ReplayEngine
|
||||||
|
|
||||||
|
raw = np.random.randn(1, 32, 1024) + 1j * np.random.randn(1, 32, 1024)
|
||||||
|
with tempfile.NamedTemporaryFile(suffix=".npy", delete=False) as f:
|
||||||
|
np.save(f, raw)
|
||||||
|
tmp = f.name
|
||||||
|
try:
|
||||||
|
engine = ReplayEngine(tmp)
|
||||||
|
with self.assertRaises(RuntimeError):
|
||||||
|
engine.get_frame(0)
|
||||||
|
finally:
|
||||||
|
os.unlink(tmp)
|
||||||
|
|
||||||
|
|
||||||
|
class TestReplayEngineHDF5(unittest.TestCase):
|
||||||
|
"""ReplayEngine loading from HDF5 recordings."""
|
||||||
|
|
||||||
|
def _skip_no_h5py(self):
|
||||||
|
try:
|
||||||
|
import h5py # noqa: F401
|
||||||
|
except ImportError:
|
||||||
|
self.skipTest("h5py not installed")
|
||||||
|
|
||||||
|
def test_load_hdf5_synthetic(self):
|
||||||
|
"""Synthetic HDF5 loads and iterates frames."""
|
||||||
|
self._skip_no_h5py()
|
||||||
|
import tempfile
|
||||||
|
import h5py
|
||||||
|
from v7.replay import ReplayEngine, ReplayFormat
|
||||||
|
from radar_protocol import RadarFrame
|
||||||
|
|
||||||
|
with tempfile.NamedTemporaryFile(suffix=".h5", delete=False) as f:
|
||||||
|
tmp = f.name
|
||||||
|
|
||||||
|
try:
|
||||||
|
with h5py.File(tmp, "w") as hf:
|
||||||
|
hf.attrs["creator"] = "test"
|
||||||
|
hf.attrs["range_bins"] = 64
|
||||||
|
hf.attrs["doppler_bins"] = 32
|
||||||
|
grp = hf.create_group("frames")
|
||||||
|
for i in range(3):
|
||||||
|
fg = grp.create_group(f"frame_{i:06d}")
|
||||||
|
fg.attrs["timestamp"] = float(i)
|
||||||
|
fg.attrs["frame_number"] = i
|
||||||
|
fg.attrs["detection_count"] = 0
|
||||||
|
fg.create_dataset("range_doppler_i",
|
||||||
|
data=np.zeros((64, 32), dtype=np.int16))
|
||||||
|
fg.create_dataset("range_doppler_q",
|
||||||
|
data=np.zeros((64, 32), dtype=np.int16))
|
||||||
|
fg.create_dataset("magnitude",
|
||||||
|
data=np.zeros((64, 32), dtype=np.float64))
|
||||||
|
fg.create_dataset("detections",
|
||||||
|
data=np.zeros((64, 32), dtype=np.uint8))
|
||||||
|
fg.create_dataset("range_profile",
|
||||||
|
data=np.zeros(64, dtype=np.float64))
|
||||||
|
|
||||||
|
engine = ReplayEngine(tmp)
|
||||||
|
self.assertEqual(engine.fmt, ReplayFormat.HDF5)
|
||||||
|
self.assertEqual(engine.total_frames, 3)
|
||||||
|
|
||||||
|
frame = engine.get_frame(1)
|
||||||
|
self.assertIsInstance(frame, RadarFrame)
|
||||||
|
self.assertEqual(frame.frame_number, 1)
|
||||||
|
self.assertEqual(frame.range_doppler_i.shape, (64, 32))
|
||||||
|
engine.close()
|
||||||
|
finally:
|
||||||
|
os.unlink(tmp)
|
||||||
|
|
||||||
|
|
||||||
|
# =============================================================================
|
||||||
|
# Test: v7.processing.extract_targets_from_frame
|
||||||
|
# =============================================================================
|
||||||
|
|
||||||
|
class TestExtractTargetsFromFrame(unittest.TestCase):
|
||||||
|
"""extract_targets_from_frame bin-to-physical conversion."""
|
||||||
|
|
||||||
|
def _make_frame(self, det_cells=None):
|
||||||
|
"""Create a minimal RadarFrame with optional detection cells."""
|
||||||
|
from radar_protocol import RadarFrame
|
||||||
|
frame = RadarFrame()
|
||||||
|
if det_cells:
|
||||||
|
for rbin, dbin in det_cells:
|
||||||
|
frame.detections[rbin, dbin] = 1
|
||||||
|
frame.magnitude[rbin, dbin] = 1000.0
|
||||||
|
frame.detection_count = int(frame.detections.sum())
|
||||||
|
frame.timestamp = 1.0
|
||||||
|
return frame
|
||||||
|
|
||||||
|
def test_no_detections(self):
|
||||||
|
from v7.processing import extract_targets_from_frame
|
||||||
|
frame = self._make_frame()
|
||||||
|
targets = extract_targets_from_frame(frame)
|
||||||
|
self.assertEqual(len(targets), 0)
|
||||||
|
|
||||||
|
def test_single_detection_range(self):
|
||||||
|
"""Detection at range bin 10 → range = 10 * range_resolution."""
|
||||||
|
from v7.processing import extract_targets_from_frame
|
||||||
|
frame = self._make_frame(det_cells=[(10, 16)]) # dbin=16 = center → vel=0
|
||||||
|
targets = extract_targets_from_frame(frame, range_resolution=5.621)
|
||||||
|
self.assertEqual(len(targets), 1)
|
||||||
|
self.assertAlmostEqual(targets[0].range, 10 * 5.621, places=2)
|
||||||
|
self.assertAlmostEqual(targets[0].velocity, 0.0, places=2)
|
||||||
|
|
||||||
|
def test_velocity_sign(self):
|
||||||
|
"""Doppler bin < center → negative velocity, > center → positive."""
|
||||||
|
from v7.processing import extract_targets_from_frame
|
||||||
|
frame = self._make_frame(det_cells=[(5, 10), (5, 20)])
|
||||||
|
targets = extract_targets_from_frame(frame, velocity_resolution=1.484)
|
||||||
|
# dbin=10: vel = (10-16)*1.484 = -8.904 (approaching)
|
||||||
|
# dbin=20: vel = (20-16)*1.484 = +5.936 (receding)
|
||||||
|
self.assertLess(targets[0].velocity, 0)
|
||||||
|
self.assertGreater(targets[1].velocity, 0)
|
||||||
|
|
||||||
|
def test_snr_positive_for_nonzero_mag(self):
|
||||||
|
from v7.processing import extract_targets_from_frame
|
||||||
|
frame = self._make_frame(det_cells=[(3, 16)])
|
||||||
|
targets = extract_targets_from_frame(frame)
|
||||||
|
self.assertGreater(targets[0].snr, 0)
|
||||||
|
|
||||||
|
def test_gps_georef(self):
|
||||||
|
"""With GPS data, targets get non-zero lat/lon."""
|
||||||
|
from v7.processing import extract_targets_from_frame
|
||||||
|
from v7.models import GPSData
|
||||||
|
gps = GPSData(latitude=41.9, longitude=12.5, altitude=0.0,
|
||||||
|
pitch=0.0, heading=90.0)
|
||||||
|
frame = self._make_frame(det_cells=[(10, 16)])
|
||||||
|
targets = extract_targets_from_frame(
|
||||||
|
frame, range_resolution=100.0, gps=gps)
|
||||||
|
# Should be roughly east of radar position
|
||||||
|
self.assertAlmostEqual(targets[0].latitude, 41.9, places=2)
|
||||||
|
self.assertGreater(targets[0].longitude, 12.5)
|
||||||
|
|
||||||
|
def test_multiple_detections(self):
|
||||||
|
from v7.processing import extract_targets_from_frame
|
||||||
|
frame = self._make_frame(det_cells=[(0, 0), (10, 10), (63, 31)])
|
||||||
|
targets = extract_targets_from_frame(frame)
|
||||||
|
self.assertEqual(len(targets), 3)
|
||||||
|
# IDs should be sequential 0, 1, 2
|
||||||
|
self.assertEqual([t.id for t in targets], [0, 1, 2])
|
||||||
|
|
||||||
|
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
# Helper: lazy import of v7.models
|
# Helper: lazy import of v7.models
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
|
|||||||
@@ -14,6 +14,7 @@ from .models import (
|
|||||||
GPSData,
|
GPSData,
|
||||||
ProcessingConfig,
|
ProcessingConfig,
|
||||||
TileServer,
|
TileServer,
|
||||||
|
WaveformConfig,
|
||||||
DARK_BG, DARK_FG, DARK_ACCENT, DARK_HIGHLIGHT, DARK_BORDER,
|
DARK_BG, DARK_FG, DARK_ACCENT, DARK_HIGHLIGHT, DARK_BORDER,
|
||||||
DARK_TEXT, DARK_BUTTON, DARK_BUTTON_HOVER,
|
DARK_TEXT, DARK_BUTTON, DARK_BUTTON_HOVER,
|
||||||
DARK_TREEVIEW, DARK_TREEVIEW_ALT,
|
DARK_TREEVIEW, DARK_TREEVIEW_ALT,
|
||||||
@@ -25,7 +26,6 @@ from .models import (
|
|||||||
# Hardware interfaces — production protocol via radar_protocol.py
|
# Hardware interfaces — production protocol via radar_protocol.py
|
||||||
from .hardware import (
|
from .hardware import (
|
||||||
FT2232HConnection,
|
FT2232HConnection,
|
||||||
ReplayConnection,
|
|
||||||
RadarProtocol,
|
RadarProtocol,
|
||||||
Opcode,
|
Opcode,
|
||||||
RadarAcquisition,
|
RadarAcquisition,
|
||||||
@@ -40,31 +40,48 @@ from .processing import (
|
|||||||
RadarProcessor,
|
RadarProcessor,
|
||||||
USBPacketParser,
|
USBPacketParser,
|
||||||
apply_pitch_correction,
|
apply_pitch_correction,
|
||||||
)
|
|
||||||
|
|
||||||
# Workers and simulator
|
|
||||||
from .workers import (
|
|
||||||
RadarDataWorker,
|
|
||||||
GPSDataWorker,
|
|
||||||
TargetSimulator,
|
|
||||||
polar_to_geographic,
|
polar_to_geographic,
|
||||||
|
extract_targets_from_frame,
|
||||||
)
|
)
|
||||||
|
|
||||||
# Map widget
|
# Software FPGA (depends on golden_reference.py in FPGA cosim tree)
|
||||||
from .map_widget import (
|
try: # noqa: SIM105
|
||||||
MapBridge,
|
from .software_fpga import SoftwareFPGA, quantize_raw_iq
|
||||||
RadarMapWidget,
|
except ImportError: # golden_reference.py not available (e.g. deployment without FPGA tree)
|
||||||
)
|
pass
|
||||||
|
|
||||||
# Main dashboard
|
# Replay engine (no PyQt6 dependency, but needs SoftwareFPGA for raw IQ path)
|
||||||
from .dashboard import (
|
try: # noqa: SIM105
|
||||||
RadarDashboard,
|
from .replay import ReplayEngine, ReplayFormat
|
||||||
RangeDopplerCanvas,
|
except ImportError: # software_fpga unavailable → replay also unavailable
|
||||||
)
|
pass
|
||||||
|
|
||||||
|
# Workers, map widget, and dashboard require PyQt6 — import lazily so that
|
||||||
|
# tests/CI environments without PyQt6 can still access models/hardware/processing.
|
||||||
|
try:
|
||||||
|
from .workers import (
|
||||||
|
RadarDataWorker,
|
||||||
|
GPSDataWorker,
|
||||||
|
TargetSimulator,
|
||||||
|
ReplayWorker,
|
||||||
|
)
|
||||||
|
|
||||||
|
from .map_widget import (
|
||||||
|
MapBridge,
|
||||||
|
RadarMapWidget,
|
||||||
|
)
|
||||||
|
|
||||||
|
from .dashboard import (
|
||||||
|
RadarDashboard,
|
||||||
|
RangeDopplerCanvas,
|
||||||
|
)
|
||||||
|
except ImportError: # PyQt6 not installed (e.g. CI headless runner)
|
||||||
|
pass
|
||||||
|
|
||||||
__all__ = [ # noqa: RUF022
|
__all__ = [ # noqa: RUF022
|
||||||
# models
|
# models
|
||||||
"RadarTarget", "RadarSettings", "GPSData", "ProcessingConfig", "TileServer",
|
"RadarTarget", "RadarSettings", "GPSData", "ProcessingConfig", "TileServer",
|
||||||
|
"WaveformConfig",
|
||||||
"DARK_BG", "DARK_FG", "DARK_ACCENT", "DARK_HIGHLIGHT", "DARK_BORDER",
|
"DARK_BG", "DARK_FG", "DARK_ACCENT", "DARK_HIGHLIGHT", "DARK_BORDER",
|
||||||
"DARK_TEXT", "DARK_BUTTON", "DARK_BUTTON_HOVER",
|
"DARK_TEXT", "DARK_BUTTON", "DARK_BUTTON_HOVER",
|
||||||
"DARK_TREEVIEW", "DARK_TREEVIEW_ALT",
|
"DARK_TREEVIEW", "DARK_TREEVIEW_ALT",
|
||||||
@@ -72,15 +89,18 @@ __all__ = [ # noqa: RUF022
|
|||||||
"USB_AVAILABLE", "FTDI_AVAILABLE", "SCIPY_AVAILABLE",
|
"USB_AVAILABLE", "FTDI_AVAILABLE", "SCIPY_AVAILABLE",
|
||||||
"SKLEARN_AVAILABLE", "FILTERPY_AVAILABLE",
|
"SKLEARN_AVAILABLE", "FILTERPY_AVAILABLE",
|
||||||
# hardware — production FPGA protocol
|
# hardware — production FPGA protocol
|
||||||
"FT2232HConnection", "ReplayConnection", "RadarProtocol", "Opcode",
|
"FT2232HConnection", "RadarProtocol", "Opcode",
|
||||||
"RadarAcquisition", "RadarFrame", "StatusResponse", "DataRecorder",
|
"RadarAcquisition", "RadarFrame", "StatusResponse", "DataRecorder",
|
||||||
"STM32USBInterface",
|
"STM32USBInterface",
|
||||||
# processing
|
# processing
|
||||||
"RadarProcessor", "USBPacketParser",
|
"RadarProcessor", "USBPacketParser",
|
||||||
"apply_pitch_correction",
|
"apply_pitch_correction", "polar_to_geographic",
|
||||||
|
"extract_targets_from_frame",
|
||||||
|
# software FPGA + replay
|
||||||
|
"SoftwareFPGA", "quantize_raw_iq",
|
||||||
|
"ReplayEngine", "ReplayFormat",
|
||||||
# workers
|
# workers
|
||||||
"RadarDataWorker", "GPSDataWorker", "TargetSimulator",
|
"RadarDataWorker", "GPSDataWorker", "TargetSimulator", "ReplayWorker",
|
||||||
"polar_to_geographic",
|
|
||||||
# map
|
# map
|
||||||
"MapBridge", "RadarMapWidget",
|
"MapBridge", "RadarMapWidget",
|
||||||
# dashboard
|
# dashboard
|
||||||
|
|||||||
@@ -0,0 +1,222 @@
|
|||||||
|
"""
|
||||||
|
v7.agc_sim -- Bit-accurate AGC simulation matching rx_gain_control.v.
|
||||||
|
|
||||||
|
Provides stateful, frame-by-frame AGC processing for the Raw IQ Replay
|
||||||
|
mode and offline analysis. All gain encoding, clamping, and attack/decay/
|
||||||
|
holdoff logic is identical to the FPGA RTL.
|
||||||
|
|
||||||
|
Classes:
|
||||||
|
- AGCState -- mutable internal AGC state (gain, holdoff counter)
|
||||||
|
- AGCFrameResult -- per-frame AGC metrics after processing
|
||||||
|
|
||||||
|
Functions:
|
||||||
|
- signed_to_encoding -- signed gain (-7..+7) -> 4-bit encoding
|
||||||
|
- encoding_to_signed -- 4-bit encoding -> signed gain
|
||||||
|
- clamp_gain -- clamp to [-7, +7]
|
||||||
|
- apply_gain_shift -- apply gain_shift to 16-bit IQ arrays
|
||||||
|
- process_agc_frame -- run one frame through AGC, update state
|
||||||
|
"""
|
||||||
|
|
||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
|
from dataclasses import dataclass, field
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# FPGA AGC parameters (rx_gain_control.v reset defaults)
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
AGC_TARGET_DEFAULT = 200 # host_agc_target (8-bit)
|
||||||
|
AGC_ATTACK_DEFAULT = 1 # host_agc_attack (4-bit)
|
||||||
|
AGC_DECAY_DEFAULT = 1 # host_agc_decay (4-bit)
|
||||||
|
AGC_HOLDOFF_DEFAULT = 4 # host_agc_holdoff (4-bit)
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Gain encoding helpers (match RTL signed_to_encoding / encoding_to_signed)
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
|
||||||
|
def signed_to_encoding(g: int) -> int:
|
||||||
|
"""Convert signed gain (-7..+7) to gain_shift[3:0] encoding.
|
||||||
|
|
||||||
|
[3]=0, [2:0]=N -> amplify (left shift) by N
|
||||||
|
[3]=1, [2:0]=N -> attenuate (right shift) by N
|
||||||
|
"""
|
||||||
|
if g >= 0:
|
||||||
|
return g & 0x07
|
||||||
|
return 0x08 | ((-g) & 0x07)
|
||||||
|
|
||||||
|
|
||||||
|
def encoding_to_signed(enc: int) -> int:
|
||||||
|
"""Convert gain_shift[3:0] encoding to signed gain."""
|
||||||
|
if (enc & 0x08) == 0:
|
||||||
|
return enc & 0x07
|
||||||
|
return -(enc & 0x07)
|
||||||
|
|
||||||
|
|
||||||
|
def clamp_gain(val: int) -> int:
|
||||||
|
"""Clamp to [-7, +7] (matches RTL clamp_gain function)."""
|
||||||
|
return max(-7, min(7, val))
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Apply gain shift to IQ data (matches RTL combinational logic)
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
|
||||||
|
def apply_gain_shift(
|
||||||
|
frame_i: np.ndarray,
|
||||||
|
frame_q: np.ndarray,
|
||||||
|
gain_enc: int,
|
||||||
|
) -> tuple[np.ndarray, np.ndarray, int]:
|
||||||
|
"""Apply gain_shift encoding to 16-bit signed IQ arrays.
|
||||||
|
|
||||||
|
Returns (shifted_i, shifted_q, overflow_count).
|
||||||
|
Matches the RTL: left shift = amplify, right shift = attenuate,
|
||||||
|
saturate to +/-32767 on overflow.
|
||||||
|
"""
|
||||||
|
direction = (gain_enc >> 3) & 1 # 0=amplify, 1=attenuate
|
||||||
|
amount = gain_enc & 0x07
|
||||||
|
|
||||||
|
if amount == 0:
|
||||||
|
return frame_i.copy(), frame_q.copy(), 0
|
||||||
|
|
||||||
|
if direction == 0:
|
||||||
|
# Left shift (amplify)
|
||||||
|
si = frame_i.astype(np.int64) * (1 << amount)
|
||||||
|
sq = frame_q.astype(np.int64) * (1 << amount)
|
||||||
|
else:
|
||||||
|
# Arithmetic right shift (attenuate)
|
||||||
|
si = frame_i.astype(np.int64) >> amount
|
||||||
|
sq = frame_q.astype(np.int64) >> amount
|
||||||
|
|
||||||
|
# Count overflows (post-shift values outside 16-bit signed range)
|
||||||
|
overflow_i = (si > 32767) | (si < -32768)
|
||||||
|
overflow_q = (sq > 32767) | (sq < -32768)
|
||||||
|
overflow_count = int((overflow_i | overflow_q).sum())
|
||||||
|
|
||||||
|
# Saturate to +/-32767
|
||||||
|
si = np.clip(si, -32768, 32767).astype(np.int16)
|
||||||
|
sq = np.clip(sq, -32768, 32767).astype(np.int16)
|
||||||
|
|
||||||
|
return si, sq, overflow_count
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# AGC state and per-frame result dataclasses
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class AGCConfig:
|
||||||
|
"""AGC tuning parameters (mirrors FPGA host registers 0x28-0x2C)."""
|
||||||
|
|
||||||
|
enabled: bool = False
|
||||||
|
target: int = AGC_TARGET_DEFAULT # 8-bit peak target
|
||||||
|
attack: int = AGC_ATTACK_DEFAULT # 4-bit attenuation step
|
||||||
|
decay: int = AGC_DECAY_DEFAULT # 4-bit gain-up step
|
||||||
|
holdoff: int = AGC_HOLDOFF_DEFAULT # 4-bit frames to hold
|
||||||
|
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class AGCState:
|
||||||
|
"""Mutable internal AGC state — persists across frames."""
|
||||||
|
|
||||||
|
gain: int = 0 # signed gain, -7..+7
|
||||||
|
holdoff_counter: int = 0 # frames remaining before gain-up allowed
|
||||||
|
was_enabled: bool = False # tracks enable transitions
|
||||||
|
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class AGCFrameResult:
|
||||||
|
"""Per-frame AGC metrics returned by process_agc_frame()."""
|
||||||
|
|
||||||
|
gain_enc: int = 0 # gain_shift[3:0] encoding applied this frame
|
||||||
|
gain_signed: int = 0 # signed gain for display
|
||||||
|
peak_mag_8bit: int = 0 # pre-gain peak magnitude (upper 8 of 15 bits)
|
||||||
|
saturation_count: int = 0 # post-gain overflow count (clamped to 255)
|
||||||
|
overflow_raw: int = 0 # raw overflow count (unclamped)
|
||||||
|
shifted_i: np.ndarray = field(default_factory=lambda: np.array([], dtype=np.int16))
|
||||||
|
shifted_q: np.ndarray = field(default_factory=lambda: np.array([], dtype=np.int16))
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Per-frame AGC processing (bit-accurate to rx_gain_control.v)
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
|
||||||
|
def quantize_iq(frame: np.ndarray) -> tuple[np.ndarray, np.ndarray]:
|
||||||
|
"""Quantize complex IQ to 16-bit signed I and Q arrays.
|
||||||
|
|
||||||
|
Input: 2-D complex array (chirps x samples) — any complex dtype.
|
||||||
|
Output: (frame_i, frame_q) as int16.
|
||||||
|
"""
|
||||||
|
frame_i = np.clip(np.round(frame.real), -32768, 32767).astype(np.int16)
|
||||||
|
frame_q = np.clip(np.round(frame.imag), -32768, 32767).astype(np.int16)
|
||||||
|
return frame_i, frame_q
|
||||||
|
|
||||||
|
|
||||||
|
def process_agc_frame(
|
||||||
|
frame_i: np.ndarray,
|
||||||
|
frame_q: np.ndarray,
|
||||||
|
config: AGCConfig,
|
||||||
|
state: AGCState,
|
||||||
|
) -> AGCFrameResult:
|
||||||
|
"""Run one frame through the FPGA AGC inner loop.
|
||||||
|
|
||||||
|
Mutates *state* in place (gain and holdoff_counter).
|
||||||
|
Returns AGCFrameResult with metrics and shifted IQ data.
|
||||||
|
|
||||||
|
Parameters
|
||||||
|
----------
|
||||||
|
frame_i, frame_q : int16 arrays (any shape, typically chirps x samples)
|
||||||
|
config : AGC tuning parameters
|
||||||
|
state : mutable AGC state from previous frame
|
||||||
|
"""
|
||||||
|
# --- PRE-gain peak measurement (RTL lines 133-135, 211-213) ---
|
||||||
|
abs_i = np.abs(frame_i.astype(np.int32))
|
||||||
|
abs_q = np.abs(frame_q.astype(np.int32))
|
||||||
|
max_iq = np.maximum(abs_i, abs_q)
|
||||||
|
frame_peak_15bit = int(max_iq.max()) if max_iq.size > 0 else 0
|
||||||
|
peak_8bit = (frame_peak_15bit >> 7) & 0xFF
|
||||||
|
|
||||||
|
# --- Handle AGC enable transition (RTL lines 250-253) ---
|
||||||
|
if config.enabled and not state.was_enabled:
|
||||||
|
state.gain = 0
|
||||||
|
state.holdoff_counter = config.holdoff
|
||||||
|
state.was_enabled = config.enabled
|
||||||
|
|
||||||
|
# --- Determine effective gain encoding ---
|
||||||
|
if config.enabled:
|
||||||
|
effective_enc = signed_to_encoding(state.gain)
|
||||||
|
else:
|
||||||
|
effective_enc = signed_to_encoding(state.gain)
|
||||||
|
|
||||||
|
# --- Apply gain shift + count POST-gain overflow ---
|
||||||
|
shifted_i, shifted_q, overflow_raw = apply_gain_shift(
|
||||||
|
frame_i, frame_q, effective_enc)
|
||||||
|
sat_count = min(255, overflow_raw)
|
||||||
|
|
||||||
|
# --- AGC update at frame boundary (RTL lines 226-246) ---
|
||||||
|
if config.enabled:
|
||||||
|
if sat_count > 0:
|
||||||
|
# Clipping: reduce gain immediately (attack)
|
||||||
|
state.gain = clamp_gain(state.gain - config.attack)
|
||||||
|
state.holdoff_counter = config.holdoff
|
||||||
|
elif peak_8bit < config.target:
|
||||||
|
# Signal too weak: increase gain after holdoff
|
||||||
|
if state.holdoff_counter == 0:
|
||||||
|
state.gain = clamp_gain(state.gain + config.decay)
|
||||||
|
else:
|
||||||
|
state.holdoff_counter -= 1
|
||||||
|
else:
|
||||||
|
# Good range (peak >= target, no sat): hold, reset holdoff
|
||||||
|
state.holdoff_counter = config.holdoff
|
||||||
|
|
||||||
|
return AGCFrameResult(
|
||||||
|
gain_enc=effective_enc,
|
||||||
|
gain_signed=state.gain if config.enabled else encoding_to_signed(effective_enc),
|
||||||
|
peak_mag_8bit=peak_8bit,
|
||||||
|
saturation_count=sat_count,
|
||||||
|
overflow_raw=overflow_raw,
|
||||||
|
shifted_i=shifted_i,
|
||||||
|
shifted_q=shifted_q,
|
||||||
|
)
|
||||||
@@ -14,7 +14,7 @@ RadarDashboard is a QMainWindow with six tabs:
|
|||||||
|
|
||||||
Uses production radar_protocol.py for all FPGA communication:
|
Uses production radar_protocol.py for all FPGA communication:
|
||||||
- FT2232HConnection for real hardware
|
- FT2232HConnection for real hardware
|
||||||
- ReplayConnection for offline .npy replay
|
- Unified replay via SoftwareFPGA + ReplayEngine + ReplayWorker
|
||||||
- Mock mode (FT2232HConnection(mock=True)) for development
|
- Mock mode (FT2232HConnection(mock=True)) for development
|
||||||
|
|
||||||
The old STM32 magic-packet start flow has been removed. FPGA registers
|
The old STM32 magic-packet start flow has been removed. FPGA registers
|
||||||
@@ -22,9 +22,12 @@ are controlled directly via 4-byte {opcode, addr, value_hi, value_lo}
|
|||||||
commands sent over FT2232H.
|
commands sent over FT2232H.
|
||||||
"""
|
"""
|
||||||
|
|
||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
import time
|
import time
|
||||||
import logging
|
import logging
|
||||||
from collections import deque
|
from collections import deque
|
||||||
|
from typing import TYPE_CHECKING
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|
||||||
@@ -32,11 +35,11 @@ from PyQt6.QtWidgets import (
|
|||||||
QMainWindow, QWidget, QVBoxLayout, QHBoxLayout, QGridLayout,
|
QMainWindow, QWidget, QVBoxLayout, QHBoxLayout, QGridLayout,
|
||||||
QTabWidget, QSplitter, QGroupBox, QFrame, QScrollArea,
|
QTabWidget, QSplitter, QGroupBox, QFrame, QScrollArea,
|
||||||
QLabel, QPushButton, QComboBox, QCheckBox,
|
QLabel, QPushButton, QComboBox, QCheckBox,
|
||||||
QDoubleSpinBox, QSpinBox, QLineEdit,
|
QDoubleSpinBox, QSpinBox, QLineEdit, QSlider, QFileDialog,
|
||||||
QTableWidget, QTableWidgetItem, QHeaderView,
|
QTableWidget, QTableWidgetItem, QHeaderView,
|
||||||
QPlainTextEdit, QStatusBar, QMessageBox,
|
QPlainTextEdit, QStatusBar, QMessageBox,
|
||||||
)
|
)
|
||||||
from PyQt6.QtCore import Qt, QTimer, pyqtSignal, pyqtSlot, QObject
|
from PyQt6.QtCore import Qt, QLocale, QTimer, pyqtSignal, pyqtSlot, QObject
|
||||||
|
|
||||||
from matplotlib.backends.backend_qtagg import FigureCanvasQTAgg
|
from matplotlib.backends.backend_qtagg import FigureCanvasQTAgg
|
||||||
from matplotlib.figure import Figure
|
from matplotlib.figure import Figure
|
||||||
@@ -52,7 +55,6 @@ from .models import (
|
|||||||
)
|
)
|
||||||
from .hardware import (
|
from .hardware import (
|
||||||
FT2232HConnection,
|
FT2232HConnection,
|
||||||
ReplayConnection,
|
|
||||||
RadarProtocol,
|
RadarProtocol,
|
||||||
RadarFrame,
|
RadarFrame,
|
||||||
StatusResponse,
|
StatusResponse,
|
||||||
@@ -60,15 +62,30 @@ from .hardware import (
|
|||||||
STM32USBInterface,
|
STM32USBInterface,
|
||||||
)
|
)
|
||||||
from .processing import RadarProcessor, USBPacketParser
|
from .processing import RadarProcessor, USBPacketParser
|
||||||
from .workers import RadarDataWorker, GPSDataWorker, TargetSimulator
|
from .workers import RadarDataWorker, GPSDataWorker, TargetSimulator, ReplayWorker
|
||||||
from .map_widget import RadarMapWidget
|
from .map_widget import RadarMapWidget
|
||||||
|
|
||||||
|
if TYPE_CHECKING:
|
||||||
|
from .software_fpga import SoftwareFPGA
|
||||||
|
from .replay import ReplayEngine
|
||||||
|
|
||||||
logger = logging.getLogger(__name__)
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
# Frame dimensions from FPGA
|
# Frame dimensions from FPGA
|
||||||
NUM_RANGE_BINS = 64
|
NUM_RANGE_BINS = 64
|
||||||
NUM_DOPPLER_BINS = 32
|
NUM_DOPPLER_BINS = 32
|
||||||
|
|
||||||
|
# Force C locale (period as decimal separator) for all QDoubleSpinBox instances.
|
||||||
|
_C_LOCALE = QLocale(QLocale.Language.C)
|
||||||
|
_C_LOCALE.setNumberOptions(QLocale.NumberOption.RejectGroupSeparator)
|
||||||
|
|
||||||
|
|
||||||
|
def _make_dspin() -> QDoubleSpinBox:
|
||||||
|
"""Create a QDoubleSpinBox with C locale (no comma decimals)."""
|
||||||
|
sb = QDoubleSpinBox()
|
||||||
|
sb.setLocale(_C_LOCALE)
|
||||||
|
return sb
|
||||||
|
|
||||||
|
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
# Range-Doppler Canvas (matplotlib)
|
# Range-Doppler Canvas (matplotlib)
|
||||||
@@ -142,6 +159,12 @@ class RadarDashboard(QMainWindow):
|
|||||||
self._gps_worker: GPSDataWorker | None = None
|
self._gps_worker: GPSDataWorker | None = None
|
||||||
self._simulator: TargetSimulator | None = None
|
self._simulator: TargetSimulator | None = None
|
||||||
|
|
||||||
|
# Replay-specific objects (created when entering replay mode)
|
||||||
|
self._replay_worker: ReplayWorker | None = None
|
||||||
|
self._replay_engine: ReplayEngine | None = None
|
||||||
|
self._software_fpga: SoftwareFPGA | None = None
|
||||||
|
self._replay_mode = False
|
||||||
|
|
||||||
# State
|
# State
|
||||||
self._running = False
|
self._running = False
|
||||||
self._demo_mode = False
|
self._demo_mode = False
|
||||||
@@ -341,7 +364,7 @@ class RadarDashboard(QMainWindow):
|
|||||||
# Row 0: connection mode + device combos + buttons
|
# Row 0: connection mode + device combos + buttons
|
||||||
ctrl_layout.addWidget(QLabel("Mode:"), 0, 0)
|
ctrl_layout.addWidget(QLabel("Mode:"), 0, 0)
|
||||||
self._mode_combo = QComboBox()
|
self._mode_combo = QComboBox()
|
||||||
self._mode_combo.addItems(["Mock", "Live FT2232H", "Replay (.npy)"])
|
self._mode_combo.addItems(["Mock", "Live FT2232H", "Replay"])
|
||||||
self._mode_combo.setCurrentIndex(0)
|
self._mode_combo.setCurrentIndex(0)
|
||||||
ctrl_layout.addWidget(self._mode_combo, 0, 1)
|
ctrl_layout.addWidget(self._mode_combo, 0, 1)
|
||||||
|
|
||||||
@@ -390,6 +413,55 @@ class RadarDashboard(QMainWindow):
|
|||||||
self._status_label_main.setAlignment(Qt.AlignmentFlag.AlignRight)
|
self._status_label_main.setAlignment(Qt.AlignmentFlag.AlignRight)
|
||||||
ctrl_layout.addWidget(self._status_label_main, 1, 5, 1, 5)
|
ctrl_layout.addWidget(self._status_label_main, 1, 5, 1, 5)
|
||||||
|
|
||||||
|
# Row 2: replay transport controls (hidden until replay mode)
|
||||||
|
self._replay_file_label = QLabel("No file loaded")
|
||||||
|
self._replay_file_label.setMinimumWidth(200)
|
||||||
|
ctrl_layout.addWidget(self._replay_file_label, 2, 0, 1, 2)
|
||||||
|
|
||||||
|
self._replay_browse_btn = QPushButton("Browse...")
|
||||||
|
self._replay_browse_btn.clicked.connect(self._browse_replay_file)
|
||||||
|
ctrl_layout.addWidget(self._replay_browse_btn, 2, 2)
|
||||||
|
|
||||||
|
self._replay_play_btn = QPushButton("Play")
|
||||||
|
self._replay_play_btn.clicked.connect(self._replay_play_pause)
|
||||||
|
ctrl_layout.addWidget(self._replay_play_btn, 2, 3)
|
||||||
|
|
||||||
|
self._replay_stop_btn = QPushButton("Stop")
|
||||||
|
self._replay_stop_btn.clicked.connect(self._replay_stop)
|
||||||
|
ctrl_layout.addWidget(self._replay_stop_btn, 2, 4)
|
||||||
|
|
||||||
|
self._replay_slider = QSlider(Qt.Orientation.Horizontal)
|
||||||
|
self._replay_slider.setMinimum(0)
|
||||||
|
self._replay_slider.setMaximum(0)
|
||||||
|
self._replay_slider.valueChanged.connect(self._replay_seek)
|
||||||
|
ctrl_layout.addWidget(self._replay_slider, 2, 5, 1, 2)
|
||||||
|
|
||||||
|
self._replay_frame_label = QLabel("0 / 0")
|
||||||
|
ctrl_layout.addWidget(self._replay_frame_label, 2, 7)
|
||||||
|
|
||||||
|
self._replay_speed_combo = QComboBox()
|
||||||
|
self._replay_speed_combo.addItems(["50 ms", "100 ms", "200 ms", "500 ms"])
|
||||||
|
self._replay_speed_combo.setCurrentIndex(1)
|
||||||
|
self._replay_speed_combo.currentIndexChanged.connect(self._replay_speed_changed)
|
||||||
|
ctrl_layout.addWidget(self._replay_speed_combo, 2, 8)
|
||||||
|
|
||||||
|
self._replay_loop_cb = QCheckBox("Loop")
|
||||||
|
self._replay_loop_cb.stateChanged.connect(self._replay_loop_changed)
|
||||||
|
ctrl_layout.addWidget(self._replay_loop_cb, 2, 9)
|
||||||
|
|
||||||
|
# Collect replay widgets to toggle visibility
|
||||||
|
self._replay_controls = [
|
||||||
|
self._replay_file_label, self._replay_browse_btn,
|
||||||
|
self._replay_play_btn, self._replay_stop_btn,
|
||||||
|
self._replay_slider, self._replay_frame_label,
|
||||||
|
self._replay_speed_combo, self._replay_loop_cb,
|
||||||
|
]
|
||||||
|
for w in self._replay_controls:
|
||||||
|
w.setVisible(False)
|
||||||
|
|
||||||
|
# Show/hide replay row when mode changes
|
||||||
|
self._mode_combo.currentTextChanged.connect(self._on_mode_changed)
|
||||||
|
|
||||||
layout.addWidget(ctrl)
|
layout.addWidget(ctrl)
|
||||||
|
|
||||||
# ---- Display area (range-doppler + targets table) ------------------
|
# ---- Display area (range-doppler + targets table) ------------------
|
||||||
@@ -452,19 +524,19 @@ class RadarDashboard(QMainWindow):
|
|||||||
pos_group = QGroupBox("Radar Position")
|
pos_group = QGroupBox("Radar Position")
|
||||||
pos_layout = QGridLayout(pos_group)
|
pos_layout = QGridLayout(pos_group)
|
||||||
|
|
||||||
self._lat_spin = QDoubleSpinBox()
|
self._lat_spin = _make_dspin()
|
||||||
self._lat_spin.setRange(-90, 90)
|
self._lat_spin.setRange(-90, 90)
|
||||||
self._lat_spin.setDecimals(6)
|
self._lat_spin.setDecimals(6)
|
||||||
self._lat_spin.setValue(self._radar_position.latitude)
|
self._lat_spin.setValue(self._radar_position.latitude)
|
||||||
self._lat_spin.valueChanged.connect(self._on_position_changed)
|
self._lat_spin.valueChanged.connect(self._on_position_changed)
|
||||||
|
|
||||||
self._lon_spin = QDoubleSpinBox()
|
self._lon_spin = _make_dspin()
|
||||||
self._lon_spin.setRange(-180, 180)
|
self._lon_spin.setRange(-180, 180)
|
||||||
self._lon_spin.setDecimals(6)
|
self._lon_spin.setDecimals(6)
|
||||||
self._lon_spin.setValue(self._radar_position.longitude)
|
self._lon_spin.setValue(self._radar_position.longitude)
|
||||||
self._lon_spin.valueChanged.connect(self._on_position_changed)
|
self._lon_spin.valueChanged.connect(self._on_position_changed)
|
||||||
|
|
||||||
self._alt_spin = QDoubleSpinBox()
|
self._alt_spin = _make_dspin()
|
||||||
self._alt_spin.setRange(0, 50000)
|
self._alt_spin.setRange(0, 50000)
|
||||||
self._alt_spin.setDecimals(1)
|
self._alt_spin.setDecimals(1)
|
||||||
self._alt_spin.setValue(0.0)
|
self._alt_spin.setValue(0.0)
|
||||||
@@ -483,7 +555,7 @@ class RadarDashboard(QMainWindow):
|
|||||||
cov_group = QGroupBox("Coverage")
|
cov_group = QGroupBox("Coverage")
|
||||||
cov_layout = QGridLayout(cov_group)
|
cov_layout = QGridLayout(cov_group)
|
||||||
|
|
||||||
self._coverage_spin = QDoubleSpinBox()
|
self._coverage_spin = _make_dspin()
|
||||||
self._coverage_spin.setRange(1, 200)
|
self._coverage_spin.setRange(1, 200)
|
||||||
self._coverage_spin.setDecimals(1)
|
self._coverage_spin.setDecimals(1)
|
||||||
self._coverage_spin.setValue(self._settings.coverage_radius / 1000)
|
self._coverage_spin.setValue(self._settings.coverage_radius / 1000)
|
||||||
@@ -899,7 +971,7 @@ class RadarDashboard(QMainWindow):
|
|||||||
for spine in self._agc_ax_sat.spines.values():
|
for spine in self._agc_ax_sat.spines.values():
|
||||||
spine.set_color(DARK_BORDER)
|
spine.set_color(DARK_BORDER)
|
||||||
self._agc_sat_line, = self._agc_ax_sat.plot(
|
self._agc_sat_line, = self._agc_ax_sat.plot(
|
||||||
[], [], color=DARK_ERROR, linewidth=1.0)
|
[], [], color=DARK_ERROR, linewidth=1.0, label="Saturation")
|
||||||
self._agc_sat_fill_artist = None
|
self._agc_sat_fill_artist = None
|
||||||
self._agc_ax_sat.legend(
|
self._agc_ax_sat.legend(
|
||||||
loc="upper right", fontsize=8,
|
loc="upper right", fontsize=8,
|
||||||
@@ -1047,7 +1119,7 @@ class RadarDashboard(QMainWindow):
|
|||||||
row += 1
|
row += 1
|
||||||
|
|
||||||
p_layout.addWidget(QLabel("DBSCAN eps:"), row, 0)
|
p_layout.addWidget(QLabel("DBSCAN eps:"), row, 0)
|
||||||
self._cluster_eps_spin = QDoubleSpinBox()
|
self._cluster_eps_spin = _make_dspin()
|
||||||
self._cluster_eps_spin.setRange(1.0, 5000.0)
|
self._cluster_eps_spin.setRange(1.0, 5000.0)
|
||||||
self._cluster_eps_spin.setDecimals(1)
|
self._cluster_eps_spin.setDecimals(1)
|
||||||
self._cluster_eps_spin.setValue(self._processing_config.clustering_eps)
|
self._cluster_eps_spin.setValue(self._processing_config.clustering_eps)
|
||||||
@@ -1164,7 +1236,11 @@ class RadarDashboard(QMainWindow):
|
|||||||
logger.error(f"Failed to send FPGA cmd: 0x{opcode:02X}")
|
logger.error(f"Failed to send FPGA cmd: 0x{opcode:02X}")
|
||||||
|
|
||||||
def _send_fpga_validated(self, opcode: int, value: int, bits: int):
|
def _send_fpga_validated(self, opcode: int, value: int, bits: int):
|
||||||
"""Clamp value to bit-width and send."""
|
"""Clamp value to bit-width and send.
|
||||||
|
|
||||||
|
In replay mode, also dispatch to the SoftwareFPGA setter and
|
||||||
|
re-process the current frame so the user sees immediate effect.
|
||||||
|
"""
|
||||||
max_val = (1 << bits) - 1
|
max_val = (1 << bits) - 1
|
||||||
clamped = max(0, min(value, max_val))
|
clamped = max(0, min(value, max_val))
|
||||||
if clamped != value:
|
if clamped != value:
|
||||||
@@ -1174,7 +1250,18 @@ class RadarDashboard(QMainWindow):
|
|||||||
key = f"0x{opcode:02X}"
|
key = f"0x{opcode:02X}"
|
||||||
if key in self._param_spins:
|
if key in self._param_spins:
|
||||||
self._param_spins[key].setValue(clamped)
|
self._param_spins[key].setValue(clamped)
|
||||||
self._send_fpga_cmd(opcode, clamped)
|
|
||||||
|
# Dispatch to real FPGA (live/mock mode)
|
||||||
|
if not self._replay_mode:
|
||||||
|
self._send_fpga_cmd(opcode, clamped)
|
||||||
|
return
|
||||||
|
|
||||||
|
# Dispatch to SoftwareFPGA (replay mode)
|
||||||
|
if self._software_fpga is not None:
|
||||||
|
self._dispatch_to_software_fpga(opcode, clamped)
|
||||||
|
# Re-process current frame so the effect is visible immediately
|
||||||
|
if self._replay_worker is not None:
|
||||||
|
self._replay_worker.seek(self._replay_worker.current_index)
|
||||||
|
|
||||||
def _send_custom_command(self):
|
def _send_custom_command(self):
|
||||||
"""Send custom opcode + value from the FPGA Control tab."""
|
"""Send custom opcode + value from the FPGA Control tab."""
|
||||||
@@ -1191,36 +1278,112 @@ class RadarDashboard(QMainWindow):
|
|||||||
|
|
||||||
def _start_radar(self):
|
def _start_radar(self):
|
||||||
"""Start radar data acquisition using production protocol."""
|
"""Start radar data acquisition using production protocol."""
|
||||||
|
# Mutual exclusion: stop demo if running
|
||||||
|
if self._demo_mode:
|
||||||
|
self._stop_demo()
|
||||||
|
|
||||||
try:
|
try:
|
||||||
mode = self._mode_combo.currentText()
|
mode = self._mode_combo.currentText()
|
||||||
|
|
||||||
if "Mock" in mode:
|
if "Mock" in mode:
|
||||||
|
self._replay_mode = False
|
||||||
self._connection = FT2232HConnection(mock=True)
|
self._connection = FT2232HConnection(mock=True)
|
||||||
if not self._connection.open():
|
if not self._connection.open():
|
||||||
QMessageBox.critical(self, "Error", "Failed to open mock connection.")
|
QMessageBox.critical(self, "Error", "Failed to open mock connection.")
|
||||||
return
|
return
|
||||||
elif "Live" in mode:
|
elif "Live" in mode:
|
||||||
|
self._replay_mode = False
|
||||||
self._connection = FT2232HConnection(mock=False)
|
self._connection = FT2232HConnection(mock=False)
|
||||||
if not self._connection.open():
|
if not self._connection.open():
|
||||||
QMessageBox.critical(self, "Error",
|
QMessageBox.critical(self, "Error",
|
||||||
"Failed to open FT2232H. Check USB connection.")
|
"Failed to open FT2232H. Check USB connection.")
|
||||||
return
|
return
|
||||||
elif "Replay" in mode:
|
elif "Replay" in mode:
|
||||||
from PyQt6.QtWidgets import QFileDialog
|
self._replay_mode = True
|
||||||
npy_dir = QFileDialog.getExistingDirectory(
|
replay_path = self._replay_file_label.text()
|
||||||
self, "Select .npy replay directory")
|
if replay_path == "No file loaded" or not replay_path:
|
||||||
if not npy_dir:
|
QMessageBox.warning(
|
||||||
|
self, "Replay",
|
||||||
|
"Use 'Browse...' to select a replay"
|
||||||
|
" file or directory first.")
|
||||||
return
|
return
|
||||||
self._connection = ReplayConnection(npy_dir)
|
|
||||||
if not self._connection.open():
|
from .software_fpga import SoftwareFPGA
|
||||||
QMessageBox.critical(self, "Error",
|
from .replay import ReplayEngine
|
||||||
"Failed to open replay connection.")
|
|
||||||
|
self._software_fpga = SoftwareFPGA()
|
||||||
|
# Enable CFAR by default for raw IQ replay (avoids 2000+ detections)
|
||||||
|
self._software_fpga.set_cfar_enable(True)
|
||||||
|
|
||||||
|
try:
|
||||||
|
self._replay_engine = ReplayEngine(
|
||||||
|
replay_path, self._software_fpga)
|
||||||
|
except (OSError, ValueError, RuntimeError) as exc:
|
||||||
|
QMessageBox.critical(self, "Replay Error",
|
||||||
|
f"Failed to open replay data:\n{exc}")
|
||||||
|
self._software_fpga = None
|
||||||
return
|
return
|
||||||
|
|
||||||
|
if self._replay_engine.total_frames == 0:
|
||||||
|
QMessageBox.warning(self, "Replay", "No frames found in the selected source.")
|
||||||
|
self._replay_engine.close()
|
||||||
|
self._replay_engine = None
|
||||||
|
self._software_fpga = None
|
||||||
|
return
|
||||||
|
|
||||||
|
speed_map = {0: 50, 1: 100, 2: 200, 3: 500}
|
||||||
|
interval = speed_map.get(self._replay_speed_combo.currentIndex(), 100)
|
||||||
|
|
||||||
|
self._replay_worker = ReplayWorker(
|
||||||
|
replay_engine=self._replay_engine,
|
||||||
|
settings=self._settings,
|
||||||
|
gps=self._radar_position,
|
||||||
|
frame_interval_ms=interval,
|
||||||
|
)
|
||||||
|
self._replay_worker.frameReady.connect(self._on_frame_ready)
|
||||||
|
self._replay_worker.targetsUpdated.connect(self._on_radar_targets)
|
||||||
|
self._replay_worker.statsUpdated.connect(self._on_radar_stats)
|
||||||
|
self._replay_worker.errorOccurred.connect(self._on_worker_error)
|
||||||
|
self._replay_worker.playbackStateChanged.connect(
|
||||||
|
self._on_playback_state_changed)
|
||||||
|
self._replay_worker.frameIndexChanged.connect(
|
||||||
|
self._on_frame_index_changed)
|
||||||
|
self._replay_worker.set_loop(self._replay_loop_cb.isChecked())
|
||||||
|
|
||||||
|
self._replay_slider.setMaximum(
|
||||||
|
self._replay_engine.total_frames - 1)
|
||||||
|
self._replay_slider.setValue(0)
|
||||||
|
self._replay_frame_label.setText(
|
||||||
|
f"0 / {self._replay_engine.total_frames}")
|
||||||
|
|
||||||
|
self._replay_worker.start()
|
||||||
|
# Update CFAR enable spinbox to reflect default-on for replay
|
||||||
|
if "0x25" in self._param_spins:
|
||||||
|
self._param_spins["0x25"].setValue(1)
|
||||||
|
|
||||||
|
# UI state
|
||||||
|
self._running = True
|
||||||
|
self._start_time = time.time()
|
||||||
|
self._frame_count = 0
|
||||||
|
self._start_btn.setEnabled(False)
|
||||||
|
self._stop_btn.setEnabled(True)
|
||||||
|
self._mode_combo.setEnabled(False)
|
||||||
|
self._demo_btn_main.setEnabled(False)
|
||||||
|
self._demo_btn_map.setEnabled(False)
|
||||||
|
n_frames = self._replay_engine.total_frames
|
||||||
|
self._status_label_main.setText(
|
||||||
|
f"Status: Replay ({n_frames} frames)")
|
||||||
|
self._sb_status.setText(f"Replay ({n_frames} frames)")
|
||||||
|
self._sb_mode.setText("Replay")
|
||||||
|
logger.info(
|
||||||
|
"Replay started: %s (%d frames)",
|
||||||
|
replay_path, n_frames)
|
||||||
|
return
|
||||||
else:
|
else:
|
||||||
QMessageBox.warning(self, "Warning", "Unknown connection mode.")
|
QMessageBox.warning(self, "Warning", "Unknown connection mode.")
|
||||||
return
|
return
|
||||||
|
|
||||||
# Start radar worker
|
# Start radar worker (mock / live — NOT replay)
|
||||||
self._radar_worker = RadarDataWorker(
|
self._radar_worker = RadarDataWorker(
|
||||||
connection=self._connection,
|
connection=self._connection,
|
||||||
processor=self._processor,
|
processor=self._processor,
|
||||||
@@ -1254,6 +1417,8 @@ class RadarDashboard(QMainWindow):
|
|||||||
self._start_btn.setEnabled(False)
|
self._start_btn.setEnabled(False)
|
||||||
self._stop_btn.setEnabled(True)
|
self._stop_btn.setEnabled(True)
|
||||||
self._mode_combo.setEnabled(False)
|
self._mode_combo.setEnabled(False)
|
||||||
|
self._demo_btn_main.setEnabled(False)
|
||||||
|
self._demo_btn_map.setEnabled(False)
|
||||||
self._status_label_main.setText(f"Status: Running ({mode})")
|
self._status_label_main.setText(f"Status: Running ({mode})")
|
||||||
self._sb_status.setText(f"Running ({mode})")
|
self._sb_status.setText(f"Running ({mode})")
|
||||||
self._sb_mode.setText(mode)
|
self._sb_mode.setText(mode)
|
||||||
@@ -1271,6 +1436,18 @@ class RadarDashboard(QMainWindow):
|
|||||||
self._radar_worker.wait(2000)
|
self._radar_worker.wait(2000)
|
||||||
self._radar_worker = None
|
self._radar_worker = None
|
||||||
|
|
||||||
|
if self._replay_worker:
|
||||||
|
self._replay_worker.stop()
|
||||||
|
self._replay_worker.wait(2000)
|
||||||
|
self._replay_worker = None
|
||||||
|
|
||||||
|
if self._replay_engine:
|
||||||
|
self._replay_engine.close()
|
||||||
|
self._replay_engine = None
|
||||||
|
|
||||||
|
self._software_fpga = None
|
||||||
|
self._replay_mode = False
|
||||||
|
|
||||||
if self._gps_worker:
|
if self._gps_worker:
|
||||||
self._gps_worker.stop()
|
self._gps_worker.stop()
|
||||||
self._gps_worker.wait(2000)
|
self._gps_worker.wait(2000)
|
||||||
@@ -1285,11 +1462,120 @@ class RadarDashboard(QMainWindow):
|
|||||||
self._start_btn.setEnabled(True)
|
self._start_btn.setEnabled(True)
|
||||||
self._stop_btn.setEnabled(False)
|
self._stop_btn.setEnabled(False)
|
||||||
self._mode_combo.setEnabled(True)
|
self._mode_combo.setEnabled(True)
|
||||||
|
self._demo_btn_main.setEnabled(True)
|
||||||
|
self._demo_btn_map.setEnabled(True)
|
||||||
self._status_label_main.setText("Status: Radar stopped")
|
self._status_label_main.setText("Status: Radar stopped")
|
||||||
self._sb_status.setText("Radar stopped")
|
self._sb_status.setText("Radar stopped")
|
||||||
self._sb_mode.setText("Idle")
|
self._sb_mode.setText("Idle")
|
||||||
logger.info("Radar system stopped")
|
logger.info("Radar system stopped")
|
||||||
|
|
||||||
|
# =====================================================================
|
||||||
|
# Replay helpers
|
||||||
|
# =====================================================================
|
||||||
|
|
||||||
|
def _on_mode_changed(self, text: str):
|
||||||
|
"""Show/hide replay transport controls based on mode selection."""
|
||||||
|
is_replay = "Replay" in text
|
||||||
|
for w in self._replay_controls:
|
||||||
|
w.setVisible(is_replay)
|
||||||
|
|
||||||
|
def _browse_replay_file(self):
|
||||||
|
"""Open file/directory picker for replay source."""
|
||||||
|
path, _ = QFileDialog.getOpenFileName(
|
||||||
|
self, "Select replay file",
|
||||||
|
"",
|
||||||
|
"All supported (*.npy *.h5);;NumPy files (*.npy);;HDF5 files (*.h5);;All files (*)",
|
||||||
|
)
|
||||||
|
if path:
|
||||||
|
self._replay_file_label.setText(path)
|
||||||
|
return
|
||||||
|
# If no file selected, try directory (for co-sim)
|
||||||
|
dir_path = QFileDialog.getExistingDirectory(
|
||||||
|
self, "Select co-sim replay directory")
|
||||||
|
if dir_path:
|
||||||
|
self._replay_file_label.setText(dir_path)
|
||||||
|
|
||||||
|
def _replay_play_pause(self):
|
||||||
|
"""Toggle play/pause on the replay worker."""
|
||||||
|
if self._replay_worker is None:
|
||||||
|
return
|
||||||
|
if self._replay_worker.is_playing:
|
||||||
|
self._replay_worker.pause()
|
||||||
|
self._replay_play_btn.setText("Play")
|
||||||
|
else:
|
||||||
|
self._replay_worker.play()
|
||||||
|
self._replay_play_btn.setText("Pause")
|
||||||
|
|
||||||
|
def _replay_stop(self):
|
||||||
|
"""Stop replay playback (keeps data loaded)."""
|
||||||
|
if self._replay_worker is not None:
|
||||||
|
self._replay_worker.pause()
|
||||||
|
self._replay_worker.seek(0)
|
||||||
|
self._replay_play_btn.setText("Play")
|
||||||
|
|
||||||
|
def _replay_seek(self, value: int):
|
||||||
|
"""Seek to a specific frame from the slider."""
|
||||||
|
if self._replay_worker is not None and not self._replay_worker.is_playing:
|
||||||
|
self._replay_worker.seek(value)
|
||||||
|
|
||||||
|
def _replay_speed_changed(self, index: int):
|
||||||
|
"""Update replay frame interval from speed combo."""
|
||||||
|
speed_map = {0: 50, 1: 100, 2: 200, 3: 500}
|
||||||
|
ms = speed_map.get(index, 100)
|
||||||
|
if self._replay_worker is not None:
|
||||||
|
self._replay_worker.set_frame_interval(ms)
|
||||||
|
|
||||||
|
def _replay_loop_changed(self, state: int):
|
||||||
|
"""Update replay loop setting."""
|
||||||
|
if self._replay_worker is not None:
|
||||||
|
self._replay_worker.set_loop(state == Qt.CheckState.Checked.value)
|
||||||
|
|
||||||
|
@pyqtSlot(str)
|
||||||
|
def _on_playback_state_changed(self, state: str):
|
||||||
|
"""Update UI when replay playback state changes."""
|
||||||
|
if state == "playing":
|
||||||
|
self._replay_play_btn.setText("Pause")
|
||||||
|
elif state in ("paused", "stopped"):
|
||||||
|
self._replay_play_btn.setText("Play")
|
||||||
|
if state == "stopped" and self._replay_worker is not None:
|
||||||
|
self._status_label_main.setText("Status: Replay finished")
|
||||||
|
|
||||||
|
@pyqtSlot(int, int)
|
||||||
|
def _on_frame_index_changed(self, current: int, total: int):
|
||||||
|
"""Update slider and frame label from replay worker."""
|
||||||
|
self._replay_slider.blockSignals(True)
|
||||||
|
self._replay_slider.setValue(current)
|
||||||
|
self._replay_slider.blockSignals(False)
|
||||||
|
self._replay_frame_label.setText(f"{current} / {total}")
|
||||||
|
|
||||||
|
def _dispatch_to_software_fpga(self, opcode: int, value: int):
|
||||||
|
"""Route an FPGA opcode+value to the SoftwareFPGA setter."""
|
||||||
|
fpga = self._software_fpga
|
||||||
|
if fpga is None:
|
||||||
|
return
|
||||||
|
_opcode_dispatch = {
|
||||||
|
0x03: lambda v: fpga.set_detect_threshold(v),
|
||||||
|
0x16: lambda v: fpga.set_gain_shift(v),
|
||||||
|
0x21: lambda v: fpga.set_cfar_guard(v),
|
||||||
|
0x22: lambda v: fpga.set_cfar_train(v),
|
||||||
|
0x23: lambda v: fpga.set_cfar_alpha(v),
|
||||||
|
0x24: lambda v: fpga.set_cfar_mode(v),
|
||||||
|
0x25: lambda v: fpga.set_cfar_enable(bool(v)),
|
||||||
|
0x26: lambda v: fpga.set_mti_enable(bool(v)),
|
||||||
|
0x27: lambda v: fpga.set_dc_notch_width(v),
|
||||||
|
0x28: lambda v: fpga.set_agc_enable(bool(v)),
|
||||||
|
0x29: lambda v: fpga.set_agc_params(target=v),
|
||||||
|
0x2A: lambda v: fpga.set_agc_params(attack=v),
|
||||||
|
0x2B: lambda v: fpga.set_agc_params(decay=v),
|
||||||
|
0x2C: lambda v: fpga.set_agc_params(holdoff=v),
|
||||||
|
}
|
||||||
|
handler = _opcode_dispatch.get(opcode)
|
||||||
|
if handler is not None:
|
||||||
|
handler(value)
|
||||||
|
logger.info(f"SoftwareFPGA: 0x{opcode:02X} = {value}")
|
||||||
|
else:
|
||||||
|
logger.debug(f"SoftwareFPGA: opcode 0x{opcode:02X} not handled (no-op)")
|
||||||
|
|
||||||
# =====================================================================
|
# =====================================================================
|
||||||
# Demo mode
|
# Demo mode
|
||||||
# =====================================================================
|
# =====================================================================
|
||||||
@@ -1297,6 +1583,10 @@ class RadarDashboard(QMainWindow):
|
|||||||
def _start_demo(self):
|
def _start_demo(self):
|
||||||
if self._simulator:
|
if self._simulator:
|
||||||
return
|
return
|
||||||
|
# Mutual exclusion: do not start demo while radar/replay is running
|
||||||
|
if self._running:
|
||||||
|
logger.warning("Cannot start demo while radar is running")
|
||||||
|
return
|
||||||
self._simulator = TargetSimulator(self._radar_position, self)
|
self._simulator = TargetSimulator(self._radar_position, self)
|
||||||
self._simulator.targetsUpdated.connect(self._on_demo_targets)
|
self._simulator.targetsUpdated.connect(self._on_demo_targets)
|
||||||
self._simulator.start(500)
|
self._simulator.start(500)
|
||||||
@@ -1315,7 +1605,7 @@ class RadarDashboard(QMainWindow):
|
|||||||
self._demo_mode = False
|
self._demo_mode = False
|
||||||
if not self._running:
|
if not self._running:
|
||||||
mode = "Idle"
|
mode = "Idle"
|
||||||
elif isinstance(self._connection, ReplayConnection):
|
elif self._replay_mode:
|
||||||
mode = "Replay"
|
mode = "Replay"
|
||||||
else:
|
else:
|
||||||
mode = "Live"
|
mode = "Live"
|
||||||
|
|||||||
@@ -3,14 +3,11 @@ v7.hardware — Hardware interface classes for the PLFM Radar GUI V7.
|
|||||||
|
|
||||||
Provides:
|
Provides:
|
||||||
- FT2232H radar data + command interface via production radar_protocol module
|
- FT2232H radar data + command interface via production radar_protocol module
|
||||||
- ReplayConnection for offline .npy replay via production radar_protocol module
|
|
||||||
- STM32USBInterface for GPS data only (USB CDC)
|
- STM32USBInterface for GPS data only (USB CDC)
|
||||||
|
|
||||||
The FT2232H interface uses the production protocol layer (radar_protocol.py)
|
The FT2232H interface uses the production protocol layer (radar_protocol.py)
|
||||||
which sends 4-byte {opcode, addr, value_hi, value_lo} register commands and
|
which sends 4-byte {opcode, addr, value_hi, value_lo} register commands and
|
||||||
parses 0xAA data / 0xBB status packets from the FPGA. The old magic-packet
|
parses 0xAA data / 0xBB status packets from the FPGA.
|
||||||
and 'SET'...'END' binary settings protocol has been removed — it was
|
|
||||||
incompatible with the FPGA register interface.
|
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import sys
|
import sys
|
||||||
@@ -28,7 +25,6 @@ if USB_AVAILABLE:
|
|||||||
sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))
|
sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))
|
||||||
from radar_protocol import ( # noqa: F401 — re-exported for v7 package
|
from radar_protocol import ( # noqa: F401 — re-exported for v7 package
|
||||||
FT2232HConnection,
|
FT2232HConnection,
|
||||||
ReplayConnection,
|
|
||||||
RadarProtocol,
|
RadarProtocol,
|
||||||
Opcode,
|
Opcode,
|
||||||
RadarAcquisition,
|
RadarAcquisition,
|
||||||
|
|||||||
@@ -17,7 +17,8 @@ from PyQt6.QtWidgets import (
|
|||||||
QWidget, QVBoxLayout, QHBoxLayout, QFrame,
|
QWidget, QVBoxLayout, QHBoxLayout, QFrame,
|
||||||
QComboBox, QCheckBox, QPushButton, QLabel,
|
QComboBox, QCheckBox, QPushButton, QLabel,
|
||||||
)
|
)
|
||||||
from PyQt6.QtCore import Qt, pyqtSignal, pyqtSlot, QObject
|
from PyQt6.QtCore import Qt, QUrl, pyqtSignal, pyqtSlot, QObject
|
||||||
|
from PyQt6.QtWebEngineCore import QWebEngineSettings
|
||||||
from PyQt6.QtWebEngineWidgets import QWebEngineView
|
from PyQt6.QtWebEngineWidgets import QWebEngineView
|
||||||
from PyQt6.QtWebChannel import QWebChannel
|
from PyQt6.QtWebChannel import QWebChannel
|
||||||
|
|
||||||
@@ -517,8 +518,20 @@ document.addEventListener('DOMContentLoaded', function() {{
|
|||||||
# ---- load / helpers ----------------------------------------------------
|
# ---- load / helpers ----------------------------------------------------
|
||||||
|
|
||||||
def _load_map(self):
|
def _load_map(self):
|
||||||
self._web_view.setHtml(self._get_map_html())
|
# Enable remote resource access so Leaflet CDN scripts/tiles can load.
|
||||||
logger.info("Leaflet map HTML loaded")
|
settings = self._web_view.page().settings()
|
||||||
|
settings.setAttribute(
|
||||||
|
QWebEngineSettings.WebAttribute.LocalContentCanAccessRemoteUrls,
|
||||||
|
True,
|
||||||
|
)
|
||||||
|
# Provide an HTTP base URL so the page has a proper origin;
|
||||||
|
# without this, setHtml() defaults to about:blank which blocks
|
||||||
|
# external resource loading in modern Chromium.
|
||||||
|
self._web_view.setHtml(
|
||||||
|
self._get_map_html(),
|
||||||
|
QUrl("http://localhost/radar_map"),
|
||||||
|
)
|
||||||
|
logger.info("Leaflet map HTML loaded (with HTTP base URL)")
|
||||||
|
|
||||||
def _on_map_ready(self):
|
def _on_map_ready(self):
|
||||||
self._status_label.setText(f"Map ready - {len(self._targets)} targets")
|
self._status_label.setText(f"Map ready - {len(self._targets)} targets")
|
||||||
|
|||||||
@@ -186,3 +186,59 @@ class TileServer(Enum):
|
|||||||
GOOGLE_SATELLITE = "google_sat"
|
GOOGLE_SATELLITE = "google_sat"
|
||||||
GOOGLE_HYBRID = "google_hybrid"
|
GOOGLE_HYBRID = "google_hybrid"
|
||||||
ESRI_SATELLITE = "esri_sat"
|
ESRI_SATELLITE = "esri_sat"
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Waveform configuration (physical parameters for bin→unit conversion)
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class WaveformConfig:
|
||||||
|
"""Physical waveform parameters for converting bins to SI units.
|
||||||
|
|
||||||
|
Encapsulates the radar waveform so that range/velocity resolution
|
||||||
|
can be derived automatically instead of hardcoded in RadarSettings.
|
||||||
|
|
||||||
|
Defaults match the ADI CN0566 Phaser capture parameters used in
|
||||||
|
the golden_reference cosim (4 MSPS, 500 MHz BW, 300 us chirp).
|
||||||
|
"""
|
||||||
|
|
||||||
|
sample_rate_hz: float = 4e6 # ADC sample rate
|
||||||
|
bandwidth_hz: float = 500e6 # Chirp bandwidth
|
||||||
|
chirp_duration_s: float = 300e-6 # Chirp ramp time
|
||||||
|
center_freq_hz: float = 10.525e9 # Carrier frequency
|
||||||
|
n_range_bins: int = 64 # After decimation
|
||||||
|
n_doppler_bins: int = 32 # After Doppler FFT
|
||||||
|
fft_size: int = 1024 # Pre-decimation FFT length
|
||||||
|
decimation_factor: int = 16 # 1024 → 64
|
||||||
|
|
||||||
|
@property
|
||||||
|
def range_resolution_m(self) -> float:
|
||||||
|
"""Meters per decimated range bin (FMCW deramped baseband).
|
||||||
|
|
||||||
|
For deramped FMCW: bin spacing = c * Fs * T / (2 * N_FFT * BW).
|
||||||
|
After decimation the bin spacing grows by *decimation_factor*.
|
||||||
|
"""
|
||||||
|
c = 299_792_458.0
|
||||||
|
raw_bin = (
|
||||||
|
c * self.sample_rate_hz * self.chirp_duration_s
|
||||||
|
/ (2.0 * self.fft_size * self.bandwidth_hz)
|
||||||
|
)
|
||||||
|
return raw_bin * self.decimation_factor
|
||||||
|
|
||||||
|
@property
|
||||||
|
def velocity_resolution_mps(self) -> float:
|
||||||
|
"""m/s per Doppler bin. lambda / (2 * n_doppler * chirp_duration)."""
|
||||||
|
c = 299_792_458.0
|
||||||
|
wavelength = c / self.center_freq_hz
|
||||||
|
return wavelength / (2.0 * self.n_doppler_bins * self.chirp_duration_s)
|
||||||
|
|
||||||
|
@property
|
||||||
|
def max_range_m(self) -> float:
|
||||||
|
"""Maximum unambiguous range in meters."""
|
||||||
|
return self.range_resolution_m * self.n_range_bins
|
||||||
|
|
||||||
|
@property
|
||||||
|
def max_velocity_mps(self) -> float:
|
||||||
|
"""Maximum unambiguous velocity (±) in m/s."""
|
||||||
|
return self.velocity_resolution_mps * self.n_doppler_bins / 2.0
|
||||||
|
|||||||
@@ -451,3 +451,103 @@ class USBPacketParser:
|
|||||||
except (ValueError, struct.error) as e:
|
except (ValueError, struct.error) as e:
|
||||||
logger.error(f"Error parsing binary GPS: {e}")
|
logger.error(f"Error parsing binary GPS: {e}")
|
||||||
return None
|
return None
|
||||||
|
|
||||||
|
|
||||||
|
# ============================================================================
|
||||||
|
# Utility: polar → geographic coordinate conversion
|
||||||
|
# ============================================================================
|
||||||
|
|
||||||
|
def polar_to_geographic(
|
||||||
|
radar_lat: float,
|
||||||
|
radar_lon: float,
|
||||||
|
range_m: float,
|
||||||
|
azimuth_deg: float,
|
||||||
|
) -> tuple:
|
||||||
|
"""Convert polar (range, azimuth) relative to radar → (lat, lon).
|
||||||
|
|
||||||
|
azimuth_deg: 0 = North, clockwise.
|
||||||
|
"""
|
||||||
|
r_earth = 6_371_000.0 # Earth radius in metres
|
||||||
|
|
||||||
|
lat1 = math.radians(radar_lat)
|
||||||
|
lon1 = math.radians(radar_lon)
|
||||||
|
bearing = math.radians(azimuth_deg)
|
||||||
|
|
||||||
|
lat2 = math.asin(
|
||||||
|
math.sin(lat1) * math.cos(range_m / r_earth)
|
||||||
|
+ math.cos(lat1) * math.sin(range_m / r_earth) * math.cos(bearing)
|
||||||
|
)
|
||||||
|
lon2 = lon1 + math.atan2(
|
||||||
|
math.sin(bearing) * math.sin(range_m / r_earth) * math.cos(lat1),
|
||||||
|
math.cos(range_m / r_earth) - math.sin(lat1) * math.sin(lat2),
|
||||||
|
)
|
||||||
|
return (math.degrees(lat2), math.degrees(lon2))
|
||||||
|
|
||||||
|
|
||||||
|
# ============================================================================
|
||||||
|
# Shared target extraction (used by both RadarDataWorker and ReplayWorker)
|
||||||
|
# ============================================================================
|
||||||
|
|
||||||
|
def extract_targets_from_frame(
|
||||||
|
frame,
|
||||||
|
range_resolution: float = 1.0,
|
||||||
|
velocity_resolution: float = 1.0,
|
||||||
|
gps: GPSData | None = None,
|
||||||
|
) -> list[RadarTarget]:
|
||||||
|
"""Extract RadarTarget list from a RadarFrame's detection mask.
|
||||||
|
|
||||||
|
This is the bin-to-physical conversion + geo-mapping shared between
|
||||||
|
the live and replay data paths.
|
||||||
|
|
||||||
|
Parameters
|
||||||
|
----------
|
||||||
|
frame : RadarFrame
|
||||||
|
Frame with populated ``detections``, ``magnitude``, ``range_doppler_i/q``.
|
||||||
|
range_resolution : float
|
||||||
|
Meters per range bin.
|
||||||
|
velocity_resolution : float
|
||||||
|
m/s per Doppler bin.
|
||||||
|
gps : GPSData | None
|
||||||
|
GPS position for geo-mapping (latitude/longitude).
|
||||||
|
|
||||||
|
Returns
|
||||||
|
-------
|
||||||
|
list[RadarTarget]
|
||||||
|
One target per detection cell.
|
||||||
|
"""
|
||||||
|
det_indices = np.argwhere(frame.detections > 0)
|
||||||
|
n_doppler = frame.detections.shape[1] if frame.detections.ndim == 2 else 32
|
||||||
|
doppler_center = n_doppler // 2
|
||||||
|
|
||||||
|
targets: list[RadarTarget] = []
|
||||||
|
for idx in det_indices:
|
||||||
|
rbin, dbin = int(idx[0]), int(idx[1])
|
||||||
|
mag = float(frame.magnitude[rbin, dbin])
|
||||||
|
snr = 10.0 * math.log10(max(mag, 1.0)) if mag > 0 else 0.0
|
||||||
|
|
||||||
|
range_m = float(rbin) * range_resolution
|
||||||
|
velocity_ms = float(dbin - doppler_center) * velocity_resolution
|
||||||
|
|
||||||
|
lat, lon, azimuth, elevation = 0.0, 0.0, 0.0, 0.0
|
||||||
|
if gps is not None:
|
||||||
|
azimuth = gps.heading
|
||||||
|
# Spread detections across ±15° sector for single-beam radar
|
||||||
|
if len(det_indices) > 1:
|
||||||
|
spread = (dbin - doppler_center) / max(doppler_center, 1) * 15.0
|
||||||
|
azimuth = gps.heading + spread
|
||||||
|
lat, lon = polar_to_geographic(
|
||||||
|
gps.latitude, gps.longitude, range_m, azimuth,
|
||||||
|
)
|
||||||
|
|
||||||
|
targets.append(RadarTarget(
|
||||||
|
id=len(targets),
|
||||||
|
range=range_m,
|
||||||
|
velocity=velocity_ms,
|
||||||
|
azimuth=azimuth,
|
||||||
|
elevation=elevation,
|
||||||
|
latitude=lat,
|
||||||
|
longitude=lon,
|
||||||
|
snr=snr,
|
||||||
|
timestamp=frame.timestamp,
|
||||||
|
))
|
||||||
|
return targets
|
||||||
|
|||||||
@@ -0,0 +1,288 @@
|
|||||||
|
"""
|
||||||
|
v7.replay — ReplayEngine: auto-detect format, load, and iterate RadarFrames.
|
||||||
|
|
||||||
|
Supports three data sources:
|
||||||
|
1. **FPGA co-sim directory** — pre-computed ``.npy`` files from golden_reference
|
||||||
|
2. **Raw IQ cube** ``.npy`` — complex baseband capture (e.g. ADI Phaser)
|
||||||
|
3. **HDF5 recording** ``.h5`` — frames captured by ``DataRecorder``
|
||||||
|
|
||||||
|
For raw IQ data the engine uses :class:`SoftwareFPGA` to run the full
|
||||||
|
bit-accurate signal chain, so changing FPGA control registers in the
|
||||||
|
dashboard re-processes the data.
|
||||||
|
"""
|
||||||
|
|
||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
|
import logging
|
||||||
|
import time
|
||||||
|
from enum import Enum, auto
|
||||||
|
from pathlib import Path
|
||||||
|
from typing import TYPE_CHECKING
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
if TYPE_CHECKING:
|
||||||
|
from .software_fpga import SoftwareFPGA
|
||||||
|
|
||||||
|
# radar_protocol is a sibling module (not inside v7/)
|
||||||
|
import sys as _sys
|
||||||
|
|
||||||
|
_GUI_DIR = str(Path(__file__).resolve().parent.parent)
|
||||||
|
if _GUI_DIR not in _sys.path:
|
||||||
|
_sys.path.insert(0, _GUI_DIR)
|
||||||
|
from radar_protocol import RadarFrame # noqa: E402
|
||||||
|
|
||||||
|
log = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
# Lazy import — h5py is optional
|
||||||
|
try:
|
||||||
|
import h5py
|
||||||
|
|
||||||
|
HDF5_AVAILABLE = True
|
||||||
|
except ImportError:
|
||||||
|
HDF5_AVAILABLE = False
|
||||||
|
|
||||||
|
|
||||||
|
class ReplayFormat(Enum):
|
||||||
|
"""Detected input format."""
|
||||||
|
|
||||||
|
COSIM_DIR = auto()
|
||||||
|
RAW_IQ_NPY = auto()
|
||||||
|
HDF5 = auto()
|
||||||
|
|
||||||
|
|
||||||
|
# ───────────────────────────────────────────────────────────────────
|
||||||
|
# Format detection
|
||||||
|
# ───────────────────────────────────────────────────────────────────
|
||||||
|
|
||||||
|
_COSIM_REQUIRED = {"doppler_map_i.npy", "doppler_map_q.npy"}
|
||||||
|
|
||||||
|
|
||||||
|
def detect_format(path: str) -> ReplayFormat:
|
||||||
|
"""Auto-detect the replay data format from *path*.
|
||||||
|
|
||||||
|
Raises
|
||||||
|
------
|
||||||
|
ValueError
|
||||||
|
If the format cannot be determined.
|
||||||
|
"""
|
||||||
|
p = Path(path)
|
||||||
|
|
||||||
|
if p.is_dir():
|
||||||
|
children = {f.name for f in p.iterdir()}
|
||||||
|
if _COSIM_REQUIRED.issubset(children):
|
||||||
|
return ReplayFormat.COSIM_DIR
|
||||||
|
msg = f"Directory {p} does not contain required co-sim files: {_COSIM_REQUIRED - children}"
|
||||||
|
raise ValueError(msg)
|
||||||
|
|
||||||
|
if p.suffix == ".h5":
|
||||||
|
return ReplayFormat.HDF5
|
||||||
|
|
||||||
|
if p.suffix == ".npy":
|
||||||
|
return ReplayFormat.RAW_IQ_NPY
|
||||||
|
|
||||||
|
msg = f"Cannot determine replay format for: {p}"
|
||||||
|
raise ValueError(msg)
|
||||||
|
|
||||||
|
|
||||||
|
# ───────────────────────────────────────────────────────────────────
|
||||||
|
# ReplayEngine
|
||||||
|
# ───────────────────────────────────────────────────────────────────
|
||||||
|
|
||||||
|
class ReplayEngine:
|
||||||
|
"""Load replay data and serve RadarFrames on demand.
|
||||||
|
|
||||||
|
Parameters
|
||||||
|
----------
|
||||||
|
path : str
|
||||||
|
File or directory path to load.
|
||||||
|
software_fpga : SoftwareFPGA | None
|
||||||
|
Required only for ``RAW_IQ_NPY`` format. For other formats the
|
||||||
|
data is already processed and the FPGA instance is ignored.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(self, path: str, software_fpga: SoftwareFPGA | None = None) -> None:
|
||||||
|
self.path = path
|
||||||
|
self.fmt = detect_format(path)
|
||||||
|
self.software_fpga = software_fpga
|
||||||
|
|
||||||
|
# Populated by _load_*
|
||||||
|
self._total_frames: int = 0
|
||||||
|
self._raw_iq: np.ndarray | None = None # for RAW_IQ_NPY
|
||||||
|
self._h5_file = None
|
||||||
|
self._h5_keys: list[str] = []
|
||||||
|
self._cosim_frame = None # single RadarFrame for co-sim
|
||||||
|
|
||||||
|
self._load()
|
||||||
|
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
# Loading
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
|
||||||
|
def _load(self) -> None:
|
||||||
|
if self.fmt is ReplayFormat.COSIM_DIR:
|
||||||
|
self._load_cosim()
|
||||||
|
elif self.fmt is ReplayFormat.RAW_IQ_NPY:
|
||||||
|
self._load_raw_iq()
|
||||||
|
elif self.fmt is ReplayFormat.HDF5:
|
||||||
|
self._load_hdf5()
|
||||||
|
|
||||||
|
def _load_cosim(self) -> None:
|
||||||
|
"""Load FPGA co-sim directory (already-processed .npy arrays).
|
||||||
|
|
||||||
|
Prefers fullchain (MTI-enabled) files when CFAR outputs are present,
|
||||||
|
so that I/Q data is consistent with the detection mask. Falls back
|
||||||
|
to the non-MTI ``doppler_map`` files when fullchain data is absent.
|
||||||
|
"""
|
||||||
|
d = Path(self.path)
|
||||||
|
|
||||||
|
# CFAR outputs (from the MTI→Doppler→DC-notch→CFAR chain)
|
||||||
|
cfar_flags = d / "fullchain_cfar_flags.npy"
|
||||||
|
cfar_mag = d / "fullchain_cfar_mag.npy"
|
||||||
|
has_cfar = cfar_flags.exists() and cfar_mag.exists()
|
||||||
|
|
||||||
|
# MTI-consistent I/Q (same chain that produced CFAR outputs)
|
||||||
|
mti_dop_i = d / "fullchain_mti_doppler_i.npy"
|
||||||
|
mti_dop_q = d / "fullchain_mti_doppler_q.npy"
|
||||||
|
has_mti_doppler = mti_dop_i.exists() and mti_dop_q.exists()
|
||||||
|
|
||||||
|
# Choose I/Q: prefer MTI-chain when CFAR data comes from that chain
|
||||||
|
if has_cfar and has_mti_doppler:
|
||||||
|
dop_i = np.load(mti_dop_i).astype(np.int16)
|
||||||
|
dop_q = np.load(mti_dop_q).astype(np.int16)
|
||||||
|
log.info("Co-sim: using fullchain MTI+Doppler I/Q (matches CFAR chain)")
|
||||||
|
else:
|
||||||
|
dop_i = np.load(d / "doppler_map_i.npy").astype(np.int16)
|
||||||
|
dop_q = np.load(d / "doppler_map_q.npy").astype(np.int16)
|
||||||
|
log.info("Co-sim: using non-MTI doppler_map I/Q")
|
||||||
|
|
||||||
|
frame = RadarFrame()
|
||||||
|
frame.range_doppler_i = dop_i
|
||||||
|
frame.range_doppler_q = dop_q
|
||||||
|
|
||||||
|
if has_cfar:
|
||||||
|
frame.detections = np.load(cfar_flags).astype(np.uint8)
|
||||||
|
frame.magnitude = np.load(cfar_mag).astype(np.float64)
|
||||||
|
else:
|
||||||
|
frame.magnitude = np.sqrt(
|
||||||
|
dop_i.astype(np.float64) ** 2 + dop_q.astype(np.float64) ** 2
|
||||||
|
)
|
||||||
|
frame.detections = np.zeros_like(dop_i, dtype=np.uint8)
|
||||||
|
|
||||||
|
frame.range_profile = frame.magnitude[:, 0]
|
||||||
|
frame.detection_count = int(frame.detections.sum())
|
||||||
|
frame.frame_number = 0
|
||||||
|
frame.timestamp = time.time()
|
||||||
|
|
||||||
|
self._cosim_frame = frame
|
||||||
|
self._total_frames = 1
|
||||||
|
log.info("Loaded co-sim directory: %s (1 frame)", self.path)
|
||||||
|
|
||||||
|
def _load_raw_iq(self) -> None:
|
||||||
|
"""Load raw complex IQ cube (.npy)."""
|
||||||
|
data = np.load(self.path, mmap_mode="r")
|
||||||
|
if data.ndim == 2:
|
||||||
|
# (chirps, samples) — single frame
|
||||||
|
data = data[np.newaxis, ...]
|
||||||
|
if data.ndim != 3:
|
||||||
|
msg = f"Expected 3-D array (frames, chirps, samples), got shape {data.shape}"
|
||||||
|
raise ValueError(msg)
|
||||||
|
self._raw_iq = data
|
||||||
|
self._total_frames = data.shape[0]
|
||||||
|
log.info(
|
||||||
|
"Loaded raw IQ: %s, shape %s (%d frames)",
|
||||||
|
self.path,
|
||||||
|
data.shape,
|
||||||
|
self._total_frames,
|
||||||
|
)
|
||||||
|
|
||||||
|
def _load_hdf5(self) -> None:
|
||||||
|
"""Load HDF5 recording (.h5)."""
|
||||||
|
if not HDF5_AVAILABLE:
|
||||||
|
msg = "h5py is required to load HDF5 recordings"
|
||||||
|
raise ImportError(msg)
|
||||||
|
self._h5_file = h5py.File(self.path, "r")
|
||||||
|
frames_grp = self._h5_file.get("frames")
|
||||||
|
if frames_grp is None:
|
||||||
|
msg = f"HDF5 file {self.path} has no 'frames' group"
|
||||||
|
raise ValueError(msg)
|
||||||
|
self._h5_keys = sorted(frames_grp.keys())
|
||||||
|
self._total_frames = len(self._h5_keys)
|
||||||
|
log.info("Loaded HDF5: %s (%d frames)", self.path, self._total_frames)
|
||||||
|
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
# Public API
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
|
||||||
|
@property
|
||||||
|
def total_frames(self) -> int:
|
||||||
|
return self._total_frames
|
||||||
|
|
||||||
|
def get_frame(self, index: int) -> RadarFrame:
|
||||||
|
"""Return the RadarFrame at *index* (0-based).
|
||||||
|
|
||||||
|
For ``RAW_IQ_NPY`` format, this runs the SoftwareFPGA chain
|
||||||
|
on the requested frame's chirps.
|
||||||
|
"""
|
||||||
|
if index < 0 or index >= self._total_frames:
|
||||||
|
msg = f"Frame index {index} out of range [0, {self._total_frames})"
|
||||||
|
raise IndexError(msg)
|
||||||
|
|
||||||
|
if self.fmt is ReplayFormat.COSIM_DIR:
|
||||||
|
return self._get_cosim(index)
|
||||||
|
if self.fmt is ReplayFormat.RAW_IQ_NPY:
|
||||||
|
return self._get_raw_iq(index)
|
||||||
|
return self._get_hdf5(index)
|
||||||
|
|
||||||
|
def close(self) -> None:
|
||||||
|
"""Release any open file handles."""
|
||||||
|
if self._h5_file is not None:
|
||||||
|
self._h5_file.close()
|
||||||
|
self._h5_file = None
|
||||||
|
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
# Per-format frame getters
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
|
||||||
|
def _get_cosim(self, _index: int) -> RadarFrame:
|
||||||
|
"""Co-sim: single static frame (index ignored).
|
||||||
|
|
||||||
|
Uses deepcopy so numpy arrays are not shared with the source,
|
||||||
|
preventing in-place mutation from corrupting cached data.
|
||||||
|
"""
|
||||||
|
import copy
|
||||||
|
frame = copy.deepcopy(self._cosim_frame)
|
||||||
|
frame.timestamp = time.time()
|
||||||
|
return frame
|
||||||
|
|
||||||
|
def _get_raw_iq(self, index: int) -> RadarFrame:
|
||||||
|
"""Raw IQ: quantize one frame and run through SoftwareFPGA."""
|
||||||
|
if self.software_fpga is None:
|
||||||
|
msg = "SoftwareFPGA is required for raw IQ replay"
|
||||||
|
raise RuntimeError(msg)
|
||||||
|
|
||||||
|
from .software_fpga import quantize_raw_iq
|
||||||
|
|
||||||
|
raw = self._raw_iq[index] # (chirps, samples) complex
|
||||||
|
iq_i, iq_q = quantize_raw_iq(raw[np.newaxis, ...])
|
||||||
|
return self.software_fpga.process_chirps(
|
||||||
|
iq_i, iq_q, frame_number=index, timestamp=time.time()
|
||||||
|
)
|
||||||
|
|
||||||
|
def _get_hdf5(self, index: int) -> RadarFrame:
|
||||||
|
"""HDF5: reconstruct RadarFrame from stored datasets."""
|
||||||
|
key = self._h5_keys[index]
|
||||||
|
grp = self._h5_file["frames"][key]
|
||||||
|
|
||||||
|
frame = RadarFrame()
|
||||||
|
frame.timestamp = float(grp.attrs.get("timestamp", time.time()))
|
||||||
|
frame.frame_number = int(grp.attrs.get("frame_number", index))
|
||||||
|
frame.detection_count = int(grp.attrs.get("detection_count", 0))
|
||||||
|
|
||||||
|
frame.range_doppler_i = np.array(grp["range_doppler_i"], dtype=np.int16)
|
||||||
|
frame.range_doppler_q = np.array(grp["range_doppler_q"], dtype=np.int16)
|
||||||
|
frame.magnitude = np.array(grp["magnitude"], dtype=np.float64)
|
||||||
|
frame.detections = np.array(grp["detections"], dtype=np.uint8)
|
||||||
|
frame.range_profile = np.array(grp["range_profile"], dtype=np.float64)
|
||||||
|
|
||||||
|
return frame
|
||||||
@@ -0,0 +1,287 @@
|
|||||||
|
"""
|
||||||
|
v7.software_fpga — Bit-accurate software replica of the AERIS-10 FPGA signal chain.
|
||||||
|
|
||||||
|
Imports processing functions directly from golden_reference.py (Option A)
|
||||||
|
to avoid code duplication. Every stage is toggleable via the same host
|
||||||
|
register interface the real FPGA exposes, so the dashboard spinboxes can
|
||||||
|
drive either backend transparently.
|
||||||
|
|
||||||
|
Signal chain order (matching RTL):
|
||||||
|
quantize → range_fft → decimator → MTI → doppler_fft → dc_notch → CFAR → RadarFrame
|
||||||
|
|
||||||
|
Usage:
|
||||||
|
fpga = SoftwareFPGA()
|
||||||
|
fpga.set_cfar_enable(True)
|
||||||
|
frame = fpga.process_chirps(iq_i, iq_q, frame_number=0)
|
||||||
|
"""
|
||||||
|
|
||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
|
import logging
|
||||||
|
import os
|
||||||
|
import sys
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Import golden_reference by adding the cosim path to sys.path
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
_GOLDEN_REF_DIR = str(
|
||||||
|
Path(__file__).resolve().parents[2] # 9_Firmware/
|
||||||
|
/ "9_2_FPGA" / "tb" / "cosim" / "real_data"
|
||||||
|
)
|
||||||
|
if _GOLDEN_REF_DIR not in sys.path:
|
||||||
|
sys.path.insert(0, _GOLDEN_REF_DIR)
|
||||||
|
|
||||||
|
from golden_reference import ( # noqa: E402
|
||||||
|
run_range_fft,
|
||||||
|
run_range_bin_decimator,
|
||||||
|
run_mti_canceller,
|
||||||
|
run_doppler_fft,
|
||||||
|
run_dc_notch,
|
||||||
|
run_cfar_ca,
|
||||||
|
run_detection,
|
||||||
|
FFT_SIZE,
|
||||||
|
DOPPLER_CHIRPS,
|
||||||
|
)
|
||||||
|
|
||||||
|
# RadarFrame lives in radar_protocol (no circular dep — protocol has no GUI)
|
||||||
|
sys.path.insert(0, str(Path(__file__).resolve().parents[1]))
|
||||||
|
from radar_protocol import RadarFrame # noqa: E402
|
||||||
|
|
||||||
|
log = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Twiddle factor file paths (relative to FPGA root)
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
_FPGA_DIR = Path(__file__).resolve().parents[2] / "9_2_FPGA"
|
||||||
|
TWIDDLE_1024 = str(_FPGA_DIR / "fft_twiddle_1024.mem")
|
||||||
|
TWIDDLE_16 = str(_FPGA_DIR / "fft_twiddle_16.mem")
|
||||||
|
|
||||||
|
# CFAR mode int→string mapping (FPGA register 0x24: 0=CA, 1=GO, 2=SO)
|
||||||
|
_CFAR_MODE_MAP = {0: "CA", 1: "GO", 2: "SO", 3: "CA"}
|
||||||
|
|
||||||
|
|
||||||
|
class SoftwareFPGA:
|
||||||
|
"""Bit-accurate replica of the AERIS-10 FPGA signal processing chain.
|
||||||
|
|
||||||
|
All registers mirror FPGA reset defaults from ``radar_system_top.v``.
|
||||||
|
Setters accept the same integer values as the FPGA host commands.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(self) -> None:
|
||||||
|
# --- FPGA register mirror (reset defaults) ---
|
||||||
|
# Detection
|
||||||
|
self.detect_threshold: int = 10_000 # 0x03
|
||||||
|
self.gain_shift: int = 0 # 0x16
|
||||||
|
|
||||||
|
# CFAR
|
||||||
|
self.cfar_enable: bool = False # 0x25
|
||||||
|
self.cfar_guard: int = 2 # 0x21
|
||||||
|
self.cfar_train: int = 8 # 0x22
|
||||||
|
self.cfar_alpha: int = 0x30 # 0x23 Q4.4
|
||||||
|
self.cfar_mode: int = 0 # 0x24 0=CA,1=GO,2=SO
|
||||||
|
|
||||||
|
# MTI
|
||||||
|
self.mti_enable: bool = False # 0x26
|
||||||
|
|
||||||
|
# DC notch
|
||||||
|
self.dc_notch_width: int = 0 # 0x27
|
||||||
|
|
||||||
|
# AGC (tracked but not applied in software chain — AGC operates
|
||||||
|
# on the analog front-end gain, which doesn't exist in replay)
|
||||||
|
self.agc_enable: bool = False # 0x28
|
||||||
|
self.agc_target: int = 200 # 0x29
|
||||||
|
self.agc_attack: int = 1 # 0x2A
|
||||||
|
self.agc_decay: int = 1 # 0x2B
|
||||||
|
self.agc_holdoff: int = 4 # 0x2C
|
||||||
|
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
# Register setters (same interface as UART commands to real FPGA)
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
def set_detect_threshold(self, val: int) -> None:
|
||||||
|
self.detect_threshold = int(val) & 0xFFFF
|
||||||
|
|
||||||
|
def set_gain_shift(self, val: int) -> None:
|
||||||
|
self.gain_shift = int(val) & 0x0F
|
||||||
|
|
||||||
|
def set_cfar_enable(self, val: bool) -> None:
|
||||||
|
self.cfar_enable = bool(val)
|
||||||
|
|
||||||
|
def set_cfar_guard(self, val: int) -> None:
|
||||||
|
self.cfar_guard = int(val) & 0x0F
|
||||||
|
|
||||||
|
def set_cfar_train(self, val: int) -> None:
|
||||||
|
self.cfar_train = max(1, int(val) & 0x1F)
|
||||||
|
|
||||||
|
def set_cfar_alpha(self, val: int) -> None:
|
||||||
|
self.cfar_alpha = int(val) & 0xFF
|
||||||
|
|
||||||
|
def set_cfar_mode(self, val: int) -> None:
|
||||||
|
self.cfar_mode = int(val) & 0x03
|
||||||
|
|
||||||
|
def set_mti_enable(self, val: bool) -> None:
|
||||||
|
self.mti_enable = bool(val)
|
||||||
|
|
||||||
|
def set_dc_notch_width(self, val: int) -> None:
|
||||||
|
self.dc_notch_width = int(val) & 0x07
|
||||||
|
|
||||||
|
def set_agc_enable(self, val: bool) -> None:
|
||||||
|
self.agc_enable = bool(val)
|
||||||
|
|
||||||
|
def set_agc_params(
|
||||||
|
self,
|
||||||
|
target: int | None = None,
|
||||||
|
attack: int | None = None,
|
||||||
|
decay: int | None = None,
|
||||||
|
holdoff: int | None = None,
|
||||||
|
) -> None:
|
||||||
|
if target is not None:
|
||||||
|
self.agc_target = int(target) & 0xFF
|
||||||
|
if attack is not None:
|
||||||
|
self.agc_attack = int(attack) & 0x0F
|
||||||
|
if decay is not None:
|
||||||
|
self.agc_decay = int(decay) & 0x0F
|
||||||
|
if holdoff is not None:
|
||||||
|
self.agc_holdoff = int(holdoff) & 0x0F
|
||||||
|
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
# Core processing: raw IQ chirps → RadarFrame
|
||||||
|
# ------------------------------------------------------------------
|
||||||
|
def process_chirps(
|
||||||
|
self,
|
||||||
|
iq_i: np.ndarray,
|
||||||
|
iq_q: np.ndarray,
|
||||||
|
frame_number: int = 0,
|
||||||
|
timestamp: float = 0.0,
|
||||||
|
) -> RadarFrame:
|
||||||
|
"""Run the full FPGA signal chain on pre-quantized 16-bit I/Q chirps.
|
||||||
|
|
||||||
|
Parameters
|
||||||
|
----------
|
||||||
|
iq_i, iq_q : ndarray, shape (n_chirps, n_samples), int16/int64
|
||||||
|
Post-DDC I/Q samples. For ADI phaser data, use
|
||||||
|
``quantize_raw_iq()`` first.
|
||||||
|
frame_number : int
|
||||||
|
Frame counter for the output RadarFrame.
|
||||||
|
timestamp : float
|
||||||
|
Timestamp for the output RadarFrame.
|
||||||
|
|
||||||
|
Returns
|
||||||
|
-------
|
||||||
|
RadarFrame
|
||||||
|
Populated frame identical to what the real FPGA would produce.
|
||||||
|
"""
|
||||||
|
n_chirps = iq_i.shape[0]
|
||||||
|
n_samples = iq_i.shape[1]
|
||||||
|
|
||||||
|
# --- Stage 1: Range FFT (per chirp) ---
|
||||||
|
range_i = np.zeros((n_chirps, n_samples), dtype=np.int64)
|
||||||
|
range_q = np.zeros((n_chirps, n_samples), dtype=np.int64)
|
||||||
|
twiddle_1024 = TWIDDLE_1024 if os.path.exists(TWIDDLE_1024) else None
|
||||||
|
for c in range(n_chirps):
|
||||||
|
range_i[c], range_q[c] = run_range_fft(
|
||||||
|
iq_i[c].astype(np.int64),
|
||||||
|
iq_q[c].astype(np.int64),
|
||||||
|
twiddle_file=twiddle_1024,
|
||||||
|
)
|
||||||
|
|
||||||
|
# --- Stage 2: Range bin decimation (1024 → 64) ---
|
||||||
|
decim_i, decim_q = run_range_bin_decimator(range_i, range_q)
|
||||||
|
|
||||||
|
# --- Stage 3: MTI canceller (pre-Doppler, per-chirp) ---
|
||||||
|
mti_i, mti_q = run_mti_canceller(decim_i, decim_q, enable=self.mti_enable)
|
||||||
|
|
||||||
|
# --- Stage 4: Doppler FFT (dual 16-pt Hamming) ---
|
||||||
|
twiddle_16 = TWIDDLE_16 if os.path.exists(TWIDDLE_16) else None
|
||||||
|
doppler_i, doppler_q = run_doppler_fft(mti_i, mti_q, twiddle_file_16=twiddle_16)
|
||||||
|
|
||||||
|
# --- Stage 5: DC notch (bin zeroing) ---
|
||||||
|
notch_i, notch_q = run_dc_notch(doppler_i, doppler_q, width=self.dc_notch_width)
|
||||||
|
|
||||||
|
# --- Stage 6: Detection ---
|
||||||
|
if self.cfar_enable:
|
||||||
|
mode_str = _CFAR_MODE_MAP.get(self.cfar_mode, "CA")
|
||||||
|
detect_flags, magnitudes, _thresholds = run_cfar_ca(
|
||||||
|
notch_i,
|
||||||
|
notch_q,
|
||||||
|
guard=self.cfar_guard,
|
||||||
|
train=self.cfar_train,
|
||||||
|
alpha_q44=self.cfar_alpha,
|
||||||
|
mode=mode_str,
|
||||||
|
)
|
||||||
|
det_mask = detect_flags.astype(np.uint8)
|
||||||
|
mag = magnitudes.astype(np.float64)
|
||||||
|
else:
|
||||||
|
mag_raw, det_indices = run_detection(
|
||||||
|
notch_i, notch_q, threshold=self.detect_threshold
|
||||||
|
)
|
||||||
|
mag = mag_raw.astype(np.float64)
|
||||||
|
det_mask = np.zeros_like(mag, dtype=np.uint8)
|
||||||
|
for idx in det_indices:
|
||||||
|
det_mask[idx[0], idx[1]] = 1
|
||||||
|
|
||||||
|
# --- Assemble RadarFrame ---
|
||||||
|
frame = RadarFrame()
|
||||||
|
frame.timestamp = timestamp
|
||||||
|
frame.frame_number = frame_number
|
||||||
|
frame.range_doppler_i = np.clip(notch_i, -32768, 32767).astype(np.int16)
|
||||||
|
frame.range_doppler_q = np.clip(notch_q, -32768, 32767).astype(np.int16)
|
||||||
|
frame.magnitude = mag
|
||||||
|
frame.detections = det_mask
|
||||||
|
frame.range_profile = np.sqrt(
|
||||||
|
notch_i[:, 0].astype(np.float64) ** 2
|
||||||
|
+ notch_q[:, 0].astype(np.float64) ** 2
|
||||||
|
)
|
||||||
|
frame.detection_count = int(det_mask.sum())
|
||||||
|
return frame
|
||||||
|
|
||||||
|
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
# Utility: quantize arbitrary complex IQ to 16-bit post-DDC format
|
||||||
|
# ---------------------------------------------------------------------------
|
||||||
|
def quantize_raw_iq(
|
||||||
|
raw_complex: np.ndarray,
|
||||||
|
n_chirps: int = DOPPLER_CHIRPS,
|
||||||
|
n_samples: int = FFT_SIZE,
|
||||||
|
peak_target: int = 200,
|
||||||
|
) -> tuple[np.ndarray, np.ndarray]:
|
||||||
|
"""Quantize complex IQ data to 16-bit signed, matching DDC output level.
|
||||||
|
|
||||||
|
Parameters
|
||||||
|
----------
|
||||||
|
raw_complex : ndarray, shape (chirps, samples) or (frames, chirps, samples)
|
||||||
|
Complex64/128 baseband IQ from SDR capture. If 3-D, the first
|
||||||
|
axis is treated as frame index and only the first frame is used.
|
||||||
|
n_chirps : int
|
||||||
|
Number of chirps to keep (default 32, matching FPGA).
|
||||||
|
n_samples : int
|
||||||
|
Number of samples per chirp to keep (default 1024, matching FFT).
|
||||||
|
peak_target : int
|
||||||
|
Target peak magnitude after scaling (default 200, matching
|
||||||
|
golden_reference INPUT_PEAK_TARGET).
|
||||||
|
|
||||||
|
Returns
|
||||||
|
-------
|
||||||
|
iq_i, iq_q : ndarray, each (n_chirps, n_samples) int64
|
||||||
|
"""
|
||||||
|
if raw_complex.ndim == 3:
|
||||||
|
# (frames, chirps, samples) — take first frame
|
||||||
|
raw_complex = raw_complex[0]
|
||||||
|
|
||||||
|
# Truncate to FPGA dimensions
|
||||||
|
block = raw_complex[:n_chirps, :n_samples]
|
||||||
|
|
||||||
|
max_abs = np.max(np.abs(block))
|
||||||
|
if max_abs == 0:
|
||||||
|
return (
|
||||||
|
np.zeros((n_chirps, n_samples), dtype=np.int64),
|
||||||
|
np.zeros((n_chirps, n_samples), dtype=np.int64),
|
||||||
|
)
|
||||||
|
|
||||||
|
scale = peak_target / max_abs
|
||||||
|
scaled = block * scale
|
||||||
|
iq_i = np.clip(np.round(np.real(scaled)).astype(np.int64), -32768, 32767)
|
||||||
|
iq_q = np.clip(np.round(np.imag(scaled)).astype(np.int64), -32768, 32767)
|
||||||
|
return iq_i, iq_q
|
||||||
@@ -13,7 +13,6 @@ All packet parsing now uses the production radar_protocol.py which matches
|
|||||||
the actual FPGA packet format (0xAA data 11-byte, 0xBB status 26-byte).
|
the actual FPGA packet format (0xAA data 11-byte, 0xBB status 26-byte).
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import math
|
|
||||||
import time
|
import time
|
||||||
import random
|
import random
|
||||||
import queue
|
import queue
|
||||||
@@ -36,58 +35,25 @@ from .processing import (
|
|||||||
RadarProcessor,
|
RadarProcessor,
|
||||||
USBPacketParser,
|
USBPacketParser,
|
||||||
apply_pitch_correction,
|
apply_pitch_correction,
|
||||||
|
polar_to_geographic,
|
||||||
)
|
)
|
||||||
|
|
||||||
logger = logging.getLogger(__name__)
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
# =============================================================================
|
|
||||||
# Utility: polar → geographic
|
|
||||||
# =============================================================================
|
|
||||||
|
|
||||||
def polar_to_geographic(
|
|
||||||
radar_lat: float,
|
|
||||||
radar_lon: float,
|
|
||||||
range_m: float,
|
|
||||||
azimuth_deg: float,
|
|
||||||
) -> tuple:
|
|
||||||
"""
|
|
||||||
Convert polar coordinates (range, azimuth) relative to radar
|
|
||||||
to geographic (latitude, longitude).
|
|
||||||
|
|
||||||
azimuth_deg: 0 = North, clockwise.
|
|
||||||
Returns (lat, lon).
|
|
||||||
"""
|
|
||||||
R = 6_371_000 # Earth radius in meters
|
|
||||||
|
|
||||||
lat1 = math.radians(radar_lat)
|
|
||||||
lon1 = math.radians(radar_lon)
|
|
||||||
bearing = math.radians(azimuth_deg)
|
|
||||||
|
|
||||||
lat2 = math.asin(
|
|
||||||
math.sin(lat1) * math.cos(range_m / R)
|
|
||||||
+ math.cos(lat1) * math.sin(range_m / R) * math.cos(bearing)
|
|
||||||
)
|
|
||||||
lon2 = lon1 + math.atan2(
|
|
||||||
math.sin(bearing) * math.sin(range_m / R) * math.cos(lat1),
|
|
||||||
math.cos(range_m / R) - math.sin(lat1) * math.sin(lat2),
|
|
||||||
)
|
|
||||||
return (math.degrees(lat2), math.degrees(lon2))
|
|
||||||
|
|
||||||
|
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
# Radar Data Worker (QThread) — production protocol
|
# Radar Data Worker (QThread) — production protocol
|
||||||
# =============================================================================
|
# =============================================================================
|
||||||
|
|
||||||
class RadarDataWorker(QThread):
|
class RadarDataWorker(QThread):
|
||||||
"""
|
"""
|
||||||
Background worker that reads radar data from FT2232H (or ReplayConnection),
|
Background worker that reads radar data from FT2232H, parses 0xAA/0xBB
|
||||||
parses 0xAA/0xBB packets via production RadarAcquisition, runs optional
|
packets via production RadarAcquisition, runs optional host-side DSP,
|
||||||
host-side DSP, and emits PyQt signals with results.
|
and emits PyQt signals with results.
|
||||||
|
|
||||||
This replaces the old V7 worker which used an incompatible packet format.
|
Uses production radar_protocol.py for all packet parsing and frame
|
||||||
Now uses production radar_protocol.py for all packet parsing and frame
|
|
||||||
assembly (11-byte 0xAA data packets → 64x32 RadarFrame).
|
assembly (11-byte 0xAA data packets → 64x32 RadarFrame).
|
||||||
|
For replay, use ReplayWorker instead.
|
||||||
|
|
||||||
Signals:
|
Signals:
|
||||||
frameReady(RadarFrame) — a complete 64x32 radar frame
|
frameReady(RadarFrame) — a complete 64x32 radar frame
|
||||||
@@ -105,7 +71,7 @@ class RadarDataWorker(QThread):
|
|||||||
|
|
||||||
def __init__(
|
def __init__(
|
||||||
self,
|
self,
|
||||||
connection, # FT2232HConnection or ReplayConnection
|
connection, # FT2232HConnection
|
||||||
processor: RadarProcessor | None = None,
|
processor: RadarProcessor | None = None,
|
||||||
recorder: DataRecorder | None = None,
|
recorder: DataRecorder | None = None,
|
||||||
gps_data_ref: GPSData | None = None,
|
gps_data_ref: GPSData | None = None,
|
||||||
@@ -436,3 +402,172 @@ class TargetSimulator(QObject):
|
|||||||
|
|
||||||
self._targets = updated
|
self._targets = updated
|
||||||
self.targetsUpdated.emit(updated)
|
self.targetsUpdated.emit(updated)
|
||||||
|
|
||||||
|
|
||||||
|
# =============================================================================
|
||||||
|
# Replay Worker (QThread) — unified replay playback
|
||||||
|
# =============================================================================
|
||||||
|
|
||||||
|
class ReplayWorker(QThread):
|
||||||
|
"""Background worker for replay data playback.
|
||||||
|
|
||||||
|
Emits the same signals as ``RadarDataWorker`` so the dashboard
|
||||||
|
treats live and replay identically. Additionally emits playback
|
||||||
|
state and frame-index signals for the transport controls.
|
||||||
|
|
||||||
|
Signals
|
||||||
|
-------
|
||||||
|
frameReady(object) RadarFrame
|
||||||
|
targetsUpdated(list) list[RadarTarget]
|
||||||
|
statsUpdated(dict) processing stats
|
||||||
|
errorOccurred(str) error message
|
||||||
|
playbackStateChanged(str) "playing" | "paused" | "stopped"
|
||||||
|
frameIndexChanged(int, int) (current_index, total_frames)
|
||||||
|
"""
|
||||||
|
|
||||||
|
frameReady = pyqtSignal(object)
|
||||||
|
targetsUpdated = pyqtSignal(list)
|
||||||
|
statsUpdated = pyqtSignal(dict)
|
||||||
|
errorOccurred = pyqtSignal(str)
|
||||||
|
playbackStateChanged = pyqtSignal(str)
|
||||||
|
frameIndexChanged = pyqtSignal(int, int)
|
||||||
|
|
||||||
|
def __init__(
|
||||||
|
self,
|
||||||
|
replay_engine,
|
||||||
|
settings: RadarSettings | None = None,
|
||||||
|
gps: GPSData | None = None,
|
||||||
|
frame_interval_ms: int = 100,
|
||||||
|
parent: QObject | None = None,
|
||||||
|
) -> None:
|
||||||
|
super().__init__(parent)
|
||||||
|
import threading
|
||||||
|
|
||||||
|
from .processing import extract_targets_from_frame
|
||||||
|
from .models import WaveformConfig
|
||||||
|
|
||||||
|
self._engine = replay_engine
|
||||||
|
self._settings = settings or RadarSettings()
|
||||||
|
self._gps = gps
|
||||||
|
self._waveform = WaveformConfig()
|
||||||
|
self._frame_interval_ms = frame_interval_ms
|
||||||
|
self._extract_targets = extract_targets_from_frame
|
||||||
|
|
||||||
|
self._current_index = 0
|
||||||
|
self._last_emitted_index = 0
|
||||||
|
self._playing = False
|
||||||
|
self._stop_flag = False
|
||||||
|
self._loop = False
|
||||||
|
self._lock = threading.Lock() # guards _current_index and _emit_frame
|
||||||
|
|
||||||
|
# -- Public control API --
|
||||||
|
|
||||||
|
@property
|
||||||
|
def current_index(self) -> int:
|
||||||
|
"""Index of the last frame emitted (for re-seek on param change)."""
|
||||||
|
return self._last_emitted_index
|
||||||
|
|
||||||
|
@property
|
||||||
|
def total_frames(self) -> int:
|
||||||
|
return self._engine.total_frames
|
||||||
|
|
||||||
|
def set_gps(self, gps: GPSData | None) -> None:
|
||||||
|
self._gps = gps
|
||||||
|
|
||||||
|
def set_waveform(self, wf) -> None:
|
||||||
|
self._waveform = wf
|
||||||
|
|
||||||
|
def set_loop(self, loop: bool) -> None:
|
||||||
|
self._loop = loop
|
||||||
|
|
||||||
|
def set_frame_interval(self, ms: int) -> None:
|
||||||
|
self._frame_interval_ms = max(10, ms)
|
||||||
|
|
||||||
|
def play(self) -> None:
|
||||||
|
self._playing = True
|
||||||
|
# If at EOF, rewind so play actually does something
|
||||||
|
with self._lock:
|
||||||
|
if self._current_index >= self._engine.total_frames:
|
||||||
|
self._current_index = 0
|
||||||
|
self.playbackStateChanged.emit("playing")
|
||||||
|
|
||||||
|
def pause(self) -> None:
|
||||||
|
self._playing = False
|
||||||
|
self.playbackStateChanged.emit("paused")
|
||||||
|
|
||||||
|
def stop(self) -> None:
|
||||||
|
self._playing = False
|
||||||
|
self._stop_flag = True
|
||||||
|
self.playbackStateChanged.emit("stopped")
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_playing(self) -> bool:
|
||||||
|
"""Thread-safe read of playback state (for GUI queries)."""
|
||||||
|
return self._playing
|
||||||
|
|
||||||
|
def seek(self, index: int) -> None:
|
||||||
|
"""Jump to a specific frame and emit it (thread-safe)."""
|
||||||
|
with self._lock:
|
||||||
|
idx = max(0, min(index, self._engine.total_frames - 1))
|
||||||
|
self._current_index = idx
|
||||||
|
self._emit_frame(idx)
|
||||||
|
self._last_emitted_index = idx
|
||||||
|
|
||||||
|
# -- Thread entry --
|
||||||
|
|
||||||
|
def run(self) -> None:
|
||||||
|
self._stop_flag = False
|
||||||
|
self._playing = True
|
||||||
|
self.playbackStateChanged.emit("playing")
|
||||||
|
|
||||||
|
try:
|
||||||
|
while not self._stop_flag:
|
||||||
|
if self._playing:
|
||||||
|
with self._lock:
|
||||||
|
if self._current_index < self._engine.total_frames:
|
||||||
|
self._emit_frame(self._current_index)
|
||||||
|
self._last_emitted_index = self._current_index
|
||||||
|
self._current_index += 1
|
||||||
|
|
||||||
|
# Loop or pause at end
|
||||||
|
if self._current_index >= self._engine.total_frames:
|
||||||
|
if self._loop:
|
||||||
|
self._current_index = 0
|
||||||
|
else:
|
||||||
|
# Pause — keep thread alive for restart
|
||||||
|
self._playing = False
|
||||||
|
self.playbackStateChanged.emit("stopped")
|
||||||
|
|
||||||
|
self.msleep(self._frame_interval_ms)
|
||||||
|
except (OSError, ValueError, RuntimeError, IndexError) as exc:
|
||||||
|
self.errorOccurred.emit(str(exc))
|
||||||
|
|
||||||
|
self.playbackStateChanged.emit("stopped")
|
||||||
|
|
||||||
|
# -- Internal --
|
||||||
|
|
||||||
|
def _emit_frame(self, index: int) -> None:
|
||||||
|
try:
|
||||||
|
frame = self._engine.get_frame(index)
|
||||||
|
except (OSError, ValueError, RuntimeError, IndexError) as exc:
|
||||||
|
self.errorOccurred.emit(f"Frame {index}: {exc}")
|
||||||
|
return
|
||||||
|
|
||||||
|
self.frameReady.emit(frame)
|
||||||
|
self.frameIndexChanged.emit(index, self._engine.total_frames)
|
||||||
|
|
||||||
|
# Target extraction
|
||||||
|
targets = self._extract_targets(
|
||||||
|
frame,
|
||||||
|
range_resolution=self._waveform.range_resolution_m,
|
||||||
|
velocity_resolution=self._waveform.velocity_resolution_mps,
|
||||||
|
gps=self._gps,
|
||||||
|
)
|
||||||
|
self.targetsUpdated.emit(targets)
|
||||||
|
self.statsUpdated.emit({
|
||||||
|
"frame_number": frame.frame_number,
|
||||||
|
"detection_count": frame.detection_count,
|
||||||
|
"target_count": len(targets),
|
||||||
|
"replay_index": index,
|
||||||
|
"replay_total": self._engine.total_frames,
|
||||||
|
})
|
||||||
|
|||||||
@@ -0,0 +1,216 @@
|
|||||||
|
"""ADAR1000 vector-modulator ground-truth table and firmware parser.
|
||||||
|
|
||||||
|
This module is a pure data + helpers library imported by the cross-layer
|
||||||
|
test suite (`9_Firmware/tests/cross_layer/test_cross_layer_contract.py`,
|
||||||
|
class `TestTier2Adar1000VmTableGroundTruth`). It has no CLI entry point
|
||||||
|
and no side effects on import beyond the structural assertion on the
|
||||||
|
table length.
|
||||||
|
|
||||||
|
Ground-truth source
|
||||||
|
-------------------
|
||||||
|
The 128-entry `(I, Q)` byte pairs below are transcribed from the ADAR1000
|
||||||
|
datasheet Rev. B, Tables 13-16, page 34 ("Phase Shifter Programming"),
|
||||||
|
which is the primary normative reference. The same values appear in the
|
||||||
|
Analog Devices Linux beamformer driver
|
||||||
|
(`drivers/iio/beamformer/adar1000.c`, `adar1000_phase_values[]`) and were
|
||||||
|
cross-checked against that driver as a secondary, independent
|
||||||
|
transcription. The byte values are factual data (5-bit unsigned magnitude
|
||||||
|
in bits[4:0], polarity bit at bit[5], bits[7:6] reserved zero); no
|
||||||
|
copyrightable creative expression. Only the datasheet is the
|
||||||
|
licensing-relevant source.
|
||||||
|
|
||||||
|
PLFM_RADAR firmware indexing convention
|
||||||
|
---------------------------------------
|
||||||
|
`adarSetRxPhase` / `adarSetTxPhase` in
|
||||||
|
`9_Firmware/9_1_Microcontroller/9_1_1_C_Cpp_Libraries/ADAR1000_Manager.cpp`
|
||||||
|
write `VM_I[phase % 128]` and `VM_Q[phase % 128]` to the chip. Each index
|
||||||
|
N corresponds to commanded beam phase `N * 360/128 = N * 2.8125 deg`. The
|
||||||
|
ADI table is also on a uniform 2.8125 deg grid (verified by
|
||||||
|
`check_uniform_2p8125_deg_step` below), so a 1:1 mapping is correct:
|
||||||
|
PLFM index N == ADI table row N.
|
||||||
|
"""
|
||||||
|
|
||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
|
import re
|
||||||
|
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
# Ground truth: ADAR1000 datasheet Rev. B Tables 13-16 p.34
|
||||||
|
# Each entry: (angle_int_deg, angle_frac_x10000, vm_byte_I, vm_byte_Q)
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
GROUND_TRUTH: list[tuple[int, int, int, int]] = [
|
||||||
|
(0, 0, 0x3F, 0x20), (2, 8125, 0x3F, 0x21), (5, 6250, 0x3F, 0x23),
|
||||||
|
(8, 4375, 0x3F, 0x24), (11, 2500, 0x3F, 0x26), (14, 625, 0x3E, 0x27),
|
||||||
|
(16, 8750, 0x3E, 0x28), (19, 6875, 0x3D, 0x2A), (22, 5000, 0x3D, 0x2B),
|
||||||
|
(25, 3125, 0x3C, 0x2D), (28, 1250, 0x3C, 0x2E), (30, 9375, 0x3B, 0x2F),
|
||||||
|
(33, 7500, 0x3A, 0x30), (36, 5625, 0x39, 0x31), (39, 3750, 0x38, 0x33),
|
||||||
|
(42, 1875, 0x37, 0x34), (45, 0, 0x36, 0x35), (47, 8125, 0x35, 0x36),
|
||||||
|
(50, 6250, 0x34, 0x37), (53, 4375, 0x33, 0x38), (56, 2500, 0x32, 0x38),
|
||||||
|
(59, 625, 0x30, 0x39), (61, 8750, 0x2F, 0x3A), (64, 6875, 0x2E, 0x3A),
|
||||||
|
(67, 5000, 0x2C, 0x3B), (70, 3125, 0x2B, 0x3C), (73, 1250, 0x2A, 0x3C),
|
||||||
|
(75, 9375, 0x28, 0x3C), (78, 7500, 0x27, 0x3D), (81, 5625, 0x25, 0x3D),
|
||||||
|
(84, 3750, 0x24, 0x3D), (87, 1875, 0x22, 0x3D), (90, 0, 0x21, 0x3D),
|
||||||
|
(92, 8125, 0x01, 0x3D), (95, 6250, 0x03, 0x3D), (98, 4375, 0x04, 0x3D),
|
||||||
|
(101, 2500, 0x06, 0x3D), (104, 625, 0x07, 0x3C), (106, 8750, 0x08, 0x3C),
|
||||||
|
(109, 6875, 0x0A, 0x3C), (112, 5000, 0x0B, 0x3B), (115, 3125, 0x0D, 0x3A),
|
||||||
|
(118, 1250, 0x0E, 0x3A), (120, 9375, 0x0F, 0x39), (123, 7500, 0x11, 0x38),
|
||||||
|
(126, 5625, 0x12, 0x38), (129, 3750, 0x13, 0x37), (132, 1875, 0x14, 0x36),
|
||||||
|
(135, 0, 0x16, 0x35), (137, 8125, 0x17, 0x34), (140, 6250, 0x18, 0x33),
|
||||||
|
(143, 4375, 0x19, 0x31), (146, 2500, 0x19, 0x30), (149, 625, 0x1A, 0x2F),
|
||||||
|
(151, 8750, 0x1B, 0x2E), (154, 6875, 0x1C, 0x2D), (157, 5000, 0x1C, 0x2B),
|
||||||
|
(160, 3125, 0x1D, 0x2A), (163, 1250, 0x1E, 0x28), (165, 9375, 0x1E, 0x27),
|
||||||
|
(168, 7500, 0x1E, 0x26), (171, 5625, 0x1F, 0x24), (174, 3750, 0x1F, 0x23),
|
||||||
|
(177, 1875, 0x1F, 0x21), (180, 0, 0x1F, 0x20), (182, 8125, 0x1F, 0x01),
|
||||||
|
(185, 6250, 0x1F, 0x03), (188, 4375, 0x1F, 0x04), (191, 2500, 0x1F, 0x06),
|
||||||
|
(194, 625, 0x1E, 0x07), (196, 8750, 0x1E, 0x08), (199, 6875, 0x1D, 0x0A),
|
||||||
|
(202, 5000, 0x1D, 0x0B), (205, 3125, 0x1C, 0x0D), (208, 1250, 0x1C, 0x0E),
|
||||||
|
(210, 9375, 0x1B, 0x0F), (213, 7500, 0x1A, 0x10), (216, 5625, 0x19, 0x11),
|
||||||
|
(219, 3750, 0x18, 0x13), (222, 1875, 0x17, 0x14), (225, 0, 0x16, 0x15),
|
||||||
|
(227, 8125, 0x15, 0x16), (230, 6250, 0x14, 0x17), (233, 4375, 0x13, 0x18),
|
||||||
|
(236, 2500, 0x12, 0x18), (239, 625, 0x10, 0x19), (241, 8750, 0x0F, 0x1A),
|
||||||
|
(244, 6875, 0x0E, 0x1A), (247, 5000, 0x0C, 0x1B), (250, 3125, 0x0B, 0x1C),
|
||||||
|
(253, 1250, 0x0A, 0x1C), (255, 9375, 0x08, 0x1C), (258, 7500, 0x07, 0x1D),
|
||||||
|
(261, 5625, 0x05, 0x1D), (264, 3750, 0x04, 0x1D), (267, 1875, 0x02, 0x1D),
|
||||||
|
(270, 0, 0x01, 0x1D), (272, 8125, 0x21, 0x1D), (275, 6250, 0x23, 0x1D),
|
||||||
|
(278, 4375, 0x24, 0x1D), (281, 2500, 0x26, 0x1D), (284, 625, 0x27, 0x1C),
|
||||||
|
(286, 8750, 0x28, 0x1C), (289, 6875, 0x2A, 0x1C), (292, 5000, 0x2B, 0x1B),
|
||||||
|
(295, 3125, 0x2D, 0x1A), (298, 1250, 0x2E, 0x1A), (300, 9375, 0x2F, 0x19),
|
||||||
|
(303, 7500, 0x31, 0x18), (306, 5625, 0x32, 0x18), (309, 3750, 0x33, 0x17),
|
||||||
|
(312, 1875, 0x34, 0x16), (315, 0, 0x36, 0x15), (317, 8125, 0x37, 0x14),
|
||||||
|
(320, 6250, 0x38, 0x13), (323, 4375, 0x39, 0x11), (326, 2500, 0x39, 0x10),
|
||||||
|
(329, 625, 0x3A, 0x0F), (331, 8750, 0x3B, 0x0E), (334, 6875, 0x3C, 0x0D),
|
||||||
|
(337, 5000, 0x3C, 0x0B), (340, 3125, 0x3D, 0x0A), (343, 1250, 0x3E, 0x08),
|
||||||
|
(345, 9375, 0x3E, 0x07), (348, 7500, 0x3E, 0x06), (351, 5625, 0x3F, 0x04),
|
||||||
|
(354, 3750, 0x3F, 0x03), (357, 1875, 0x3F, 0x01),
|
||||||
|
]
|
||||||
|
|
||||||
|
assert len(GROUND_TRUTH) == 128, f"GROUND_TRUTH must have 128 entries, has {len(GROUND_TRUTH)}"
|
||||||
|
|
||||||
|
VM_I_REF: list[int] = [row[2] for row in GROUND_TRUTH]
|
||||||
|
VM_Q_REF: list[int] = [row[3] for row in GROUND_TRUTH]
|
||||||
|
|
||||||
|
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
# Structural-invariant checks on the embedded ground-truth transcription.
|
||||||
|
# These defend against typos during the copy-paste from the datasheet / ADI
|
||||||
|
# driver. Each function returns a list of error strings (empty == pass) so
|
||||||
|
# callers (the pytest class) can assert-on-empty with a useful message.
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
def check_byte_format(label: str, table: list[int]) -> list[str]:
|
||||||
|
"""Each byte must have bits[7:6] == 0 (reserved)."""
|
||||||
|
errors = []
|
||||||
|
for i, byte in enumerate(table):
|
||||||
|
if byte & 0xC0:
|
||||||
|
errors.append(f"{label}[{i}]=0x{byte:02X}: reserved bits[7:6] non-zero")
|
||||||
|
return errors
|
||||||
|
|
||||||
|
|
||||||
|
def check_uniform_2p8125_deg_step() -> list[str]:
|
||||||
|
"""Angles must form a uniform 2.8125 deg grid: angle[N] == N * 2.8125."""
|
||||||
|
errors = []
|
||||||
|
for i, (deg_int, deg_frac, _, _) in enumerate(GROUND_TRUTH):
|
||||||
|
# angle in units of 1/10000 degree; 2.8125 deg = 28125/10000 exactly
|
||||||
|
angle_e4 = deg_int * 10000 + deg_frac
|
||||||
|
expected_e4 = i * 28125
|
||||||
|
if angle_e4 != expected_e4:
|
||||||
|
errors.append(
|
||||||
|
f"GROUND_TRUTH[{i}]: angle {deg_int}.{deg_frac:04d} deg "
|
||||||
|
f"(={angle_e4}/10000) != expected {expected_e4}/10000 "
|
||||||
|
f"(=i*2.8125)"
|
||||||
|
)
|
||||||
|
return errors
|
||||||
|
|
||||||
|
|
||||||
|
def check_quadrant_symmetry() -> list[str]:
|
||||||
|
"""Angle and angle+180 deg must have inverted polarity bits but identical
|
||||||
|
magnitudes. Index offset 64 corresponds to 180 deg on the 128-step grid.
|
||||||
|
|
||||||
|
Exemption: when magnitude is zero the polarity bit is physically
|
||||||
|
meaningless (sign of zero is undefined for the IQ phasor projection).
|
||||||
|
The datasheet uses POL=1 for both 0 and 180 deg Q components (both
|
||||||
|
encode Q=0). Skip the polarity assertion for zero-magnitude entries.
|
||||||
|
"""
|
||||||
|
errors = []
|
||||||
|
POL = 0x20
|
||||||
|
MAG = 0x1F
|
||||||
|
for i in range(64):
|
||||||
|
j = i + 64
|
||||||
|
mag_i_a, mag_i_b = VM_I_REF[i] & MAG, VM_I_REF[j] & MAG
|
||||||
|
if mag_i_a != mag_i_b:
|
||||||
|
errors.append(
|
||||||
|
f"VM_I[{i}]=0x{VM_I_REF[i]:02X} vs VM_I[{j}]=0x{VM_I_REF[j]:02X}: "
|
||||||
|
f"180 deg pair has different magnitude"
|
||||||
|
)
|
||||||
|
if mag_i_a != 0 and (VM_I_REF[i] & POL) == (VM_I_REF[j] & POL):
|
||||||
|
errors.append(
|
||||||
|
f"VM_I[{i}]=0x{VM_I_REF[i]:02X} vs VM_I[{j}]=0x{VM_I_REF[j]:02X}: "
|
||||||
|
f"180 deg pair has same polarity (should be inverted, mag={mag_i_a})"
|
||||||
|
)
|
||||||
|
mag_q_a, mag_q_b = VM_Q_REF[i] & MAG, VM_Q_REF[j] & MAG
|
||||||
|
if mag_q_a != mag_q_b:
|
||||||
|
errors.append(
|
||||||
|
f"VM_Q[{i}]=0x{VM_Q_REF[i]:02X} vs VM_Q[{j}]=0x{VM_Q_REF[j]:02X}: "
|
||||||
|
f"180 deg pair has different magnitude"
|
||||||
|
)
|
||||||
|
if mag_q_a != 0 and (VM_Q_REF[i] & POL) == (VM_Q_REF[j] & POL):
|
||||||
|
errors.append(
|
||||||
|
f"VM_Q[{i}]=0x{VM_Q_REF[i]:02X} vs VM_Q[{j}]=0x{VM_Q_REF[j]:02X}: "
|
||||||
|
f"180 deg pair has same polarity (should be inverted, mag={mag_q_a})"
|
||||||
|
)
|
||||||
|
return errors
|
||||||
|
|
||||||
|
|
||||||
|
def check_cardinal_points() -> list[str]:
|
||||||
|
"""Spot-check cardinal phase points against datasheet expectations."""
|
||||||
|
errors = []
|
||||||
|
expectations = [
|
||||||
|
(0, 0x3F, 0x20, "0 deg: max +I, ~zero Q"),
|
||||||
|
(32, 0x21, 0x3D, "90 deg: ~zero I, max +Q"),
|
||||||
|
(64, 0x1F, 0x20, "180 deg: max -I, ~zero Q"),
|
||||||
|
(96, 0x01, 0x1D, "270 deg: ~zero I, max -Q"),
|
||||||
|
]
|
||||||
|
for idx, exp_i, exp_q, desc in expectations:
|
||||||
|
if VM_I_REF[idx] != exp_i or VM_Q_REF[idx] != exp_q:
|
||||||
|
errors.append(
|
||||||
|
f"index {idx} ({desc}): expected (0x{exp_i:02X}, 0x{exp_q:02X}), "
|
||||||
|
f"got (0x{VM_I_REF[idx]:02X}, 0x{VM_Q_REF[idx]:02X})"
|
||||||
|
)
|
||||||
|
return errors
|
||||||
|
|
||||||
|
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
# Parse VM_I[] / VM_Q[] from firmware C++ source.
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
ARRAY_RE = re.compile(
|
||||||
|
r"const\s+uint8_t\s+ADAR1000Manager::(?P<name>VM_I|VM_Q|VM_GAIN)\s*"
|
||||||
|
r"\[\s*128\s*\]\s*=\s*\{(?P<body>[^}]*)\}\s*;",
|
||||||
|
re.DOTALL,
|
||||||
|
)
|
||||||
|
HEX_RE = re.compile(r"0[xX][0-9a-fA-F]{1,2}")
|
||||||
|
|
||||||
|
|
||||||
|
def parse_array(source: str, name: str) -> list[int] | None:
|
||||||
|
"""Extract a 128-entry uint8_t array from C++ source by name.
|
||||||
|
|
||||||
|
Returns None if the array is not found. Returns a list (possibly shorter
|
||||||
|
than 128) of the parsed bytes if found; caller is responsible for length
|
||||||
|
validation.
|
||||||
|
|
||||||
|
LIMITATION (intentional, see PR fix/adar1000-vm-tables review finding #2):
|
||||||
|
ARRAY_RE uses `[^}]*` for the body, which terminates at the first `}`.
|
||||||
|
This is sufficient for the *flat* `const uint8_t NAME[128] = { ... };`
|
||||||
|
declarations VM_I/VM_Q use today, but it would mis-parse if the array
|
||||||
|
body ever contained nested braces (e.g. designated initialisers, struct
|
||||||
|
aggregates, or macro-expansions producing braces). If the firmware ever
|
||||||
|
needs such a form for the VM tables, replace ARRAY_RE with a balanced
|
||||||
|
brace-counting parser. Until then, the current regex is preferred for
|
||||||
|
its simplicity and the round-trip tests will catch any silent breakage.
|
||||||
|
"""
|
||||||
|
for m in ARRAY_RE.finditer(source):
|
||||||
|
if m.group("name") != name:
|
||||||
|
continue
|
||||||
|
body = m.group("body")
|
||||||
|
body = re.sub(r"//[^\n]*", "", body)
|
||||||
|
body = re.sub(r"/\*.*?\*/", "", body, flags=re.DOTALL)
|
||||||
|
return [int(tok, 16) for tok in HEX_RE.findall(body)]
|
||||||
|
return None
|
||||||
@@ -497,6 +497,7 @@ def count_concat_bits(concat_expr: str, port_widths: dict[str, int]) -> ConcatWi
|
|||||||
# Unknown width — flag it
|
# Unknown width — flag it
|
||||||
fragments.append((part, -1))
|
fragments.append((part, -1))
|
||||||
total = -1 # Can't compute
|
total = -1 # Can't compute
|
||||||
|
break
|
||||||
|
|
||||||
return ConcatWidth(
|
return ConcatWidth(
|
||||||
total_bits=total,
|
total_bits=total,
|
||||||
|
|||||||
@@ -26,11 +26,14 @@ layers agree (because both could be wrong).
|
|||||||
|
|
||||||
from __future__ import annotations
|
from __future__ import annotations
|
||||||
|
|
||||||
|
import ast
|
||||||
import os
|
import os
|
||||||
|
import re
|
||||||
import struct
|
import struct
|
||||||
import subprocess
|
import subprocess
|
||||||
import tempfile
|
import tempfile
|
||||||
from pathlib import Path
|
from pathlib import Path
|
||||||
|
from typing import ClassVar
|
||||||
|
|
||||||
import pytest
|
import pytest
|
||||||
|
|
||||||
@@ -40,6 +43,7 @@ import sys
|
|||||||
THIS_DIR = Path(__file__).resolve().parent
|
THIS_DIR = Path(__file__).resolve().parent
|
||||||
sys.path.insert(0, str(THIS_DIR))
|
sys.path.insert(0, str(THIS_DIR))
|
||||||
import contract_parser as cp # noqa: E402
|
import contract_parser as cp # noqa: E402
|
||||||
|
import adar1000_vm_reference as adar_vm # noqa: E402
|
||||||
|
|
||||||
# Also add the GUI dir to import radar_protocol
|
# Also add the GUI dir to import radar_protocol
|
||||||
sys.path.insert(0, str(cp.GUI_DIR))
|
sys.path.insert(0, str(cp.GUI_DIR))
|
||||||
@@ -49,8 +53,8 @@ sys.path.insert(0, str(cp.GUI_DIR))
|
|||||||
# Helpers
|
# Helpers
|
||||||
# ===================================================================
|
# ===================================================================
|
||||||
|
|
||||||
IVERILOG = os.environ.get("IVERILOG", "/opt/homebrew/bin/iverilog")
|
IVERILOG = os.environ.get("IVERILOG", "iverilog")
|
||||||
VVP = os.environ.get("VVP", "/opt/homebrew/bin/vvp")
|
VVP = os.environ.get("VVP", "vvp")
|
||||||
CXX = os.environ.get("CXX", "c++")
|
CXX = os.environ.get("CXX", "c++")
|
||||||
|
|
||||||
# Check tool availability for conditional skipping
|
# Check tool availability for conditional skipping
|
||||||
@@ -61,6 +65,92 @@ _has_cxx = subprocess.run(
|
|||||||
[CXX, "--version"], capture_output=True
|
[CXX, "--version"], capture_output=True
|
||||||
).returncode == 0
|
).returncode == 0
|
||||||
|
|
||||||
|
# In CI, missing tools must be a hard failure — never silently skip.
|
||||||
|
_in_ci = os.environ.get("GITHUB_ACTIONS") == "true"
|
||||||
|
if _in_ci:
|
||||||
|
if not _has_iverilog:
|
||||||
|
raise RuntimeError(
|
||||||
|
"iverilog is required in CI but was not found. "
|
||||||
|
"Ensure 'apt-get install iverilog' ran and IVERILOG/VVP are on PATH."
|
||||||
|
)
|
||||||
|
if not _has_cxx:
|
||||||
|
raise RuntimeError(
|
||||||
|
"C++ compiler is required in CI but was not found. "
|
||||||
|
"Ensure build-essential is installed."
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def _strip_cxx_comments_and_strings(src: str) -> str:
|
||||||
|
"""Return src with all C/C++ comments and string/char literals removed.
|
||||||
|
|
||||||
|
Tokenising state machine with four states:
|
||||||
|
* CODE — default; watches for `"`, `'`, `//`, `/*`
|
||||||
|
* STRING ("...") — handles `\\"` and `\\\\` escapes
|
||||||
|
* CHAR ('...') — handles `\\'` and `\\\\` escapes
|
||||||
|
* LINE_COMMENT — until next `\\n`
|
||||||
|
* BLOCK_COMMENT — until next `*/`
|
||||||
|
|
||||||
|
Used by test_vm_gain_table_is_not_reintroduced to ensure the substring
|
||||||
|
"VM_GAIN" appearing only inside an explanatory comment or a string
|
||||||
|
literal does NOT count as code reintroduction. We replace stripped
|
||||||
|
regions with a single space so token boundaries (and line counts, by
|
||||||
|
approximation — newlines preserved) are not collapsed.
|
||||||
|
"""
|
||||||
|
out: list[str] = []
|
||||||
|
i = 0
|
||||||
|
n = len(src)
|
||||||
|
CODE, STRING, CHAR, LINE_C, BLOCK_C = 0, 1, 2, 3, 4
|
||||||
|
state = CODE
|
||||||
|
while i < n:
|
||||||
|
c = src[i]
|
||||||
|
nxt = src[i + 1] if i + 1 < n else ""
|
||||||
|
if state == CODE:
|
||||||
|
if c == "/" and nxt == "/":
|
||||||
|
state = LINE_C
|
||||||
|
i += 2
|
||||||
|
elif c == "/" and nxt == "*":
|
||||||
|
state = BLOCK_C
|
||||||
|
i += 2
|
||||||
|
elif c == '"':
|
||||||
|
state = STRING
|
||||||
|
i += 1
|
||||||
|
elif c == "'":
|
||||||
|
state = CHAR
|
||||||
|
i += 1
|
||||||
|
else:
|
||||||
|
out.append(c)
|
||||||
|
i += 1
|
||||||
|
elif state == STRING:
|
||||||
|
if c == "\\" and i + 1 < n:
|
||||||
|
i += 2 # skip escape pair (handles \" and \\)
|
||||||
|
elif c == '"':
|
||||||
|
state = CODE
|
||||||
|
i += 1
|
||||||
|
else:
|
||||||
|
i += 1
|
||||||
|
elif state == CHAR:
|
||||||
|
if c == "\\" and i + 1 < n:
|
||||||
|
i += 2
|
||||||
|
elif c == "'":
|
||||||
|
state = CODE
|
||||||
|
i += 1
|
||||||
|
else:
|
||||||
|
i += 1
|
||||||
|
elif state == LINE_C:
|
||||||
|
if c == "\n":
|
||||||
|
out.append("\n") # preserve line numbering
|
||||||
|
state = CODE
|
||||||
|
i += 1
|
||||||
|
elif state == BLOCK_C:
|
||||||
|
if c == "*" and nxt == "/":
|
||||||
|
state = CODE
|
||||||
|
i += 2
|
||||||
|
else:
|
||||||
|
if c == "\n":
|
||||||
|
out.append("\n")
|
||||||
|
i += 1
|
||||||
|
return "".join(out)
|
||||||
|
|
||||||
|
|
||||||
def _parse_hex_results(text: str) -> list[dict[str, str]]:
|
def _parse_hex_results(text: str) -> list[dict[str, str]]:
|
||||||
"""Parse space-separated hex lines from TB output files."""
|
"""Parse space-separated hex lines from TB output files."""
|
||||||
@@ -355,6 +445,602 @@ class TestTier1ResetDefaults:
|
|||||||
)
|
)
|
||||||
|
|
||||||
|
|
||||||
|
class TestTier1AgcCrossLayerInvariant:
|
||||||
|
"""
|
||||||
|
Verify AGC enable/disable is consistent across FPGA, MCU, and GUI layers.
|
||||||
|
|
||||||
|
System-level invariant: the FPGA register host_agc_enable is the single
|
||||||
|
source of truth for AGC state. It propagates to MCU via DIG_6 GPIO and
|
||||||
|
to GUI via status word 4 bit[11]. At boot, all layers must agree AGC=OFF.
|
||||||
|
At runtime, the MCU must read DIG_6 every frame to sync its outer-loop AGC.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def test_fpga_dig6_drives_agc_enable(self):
|
||||||
|
"""FPGA must drive gpio_dig6 from host_agc_enable, NOT tied low."""
|
||||||
|
rtl = (cp.FPGA_DIR / "radar_system_top.v").read_text()
|
||||||
|
# Must find: assign gpio_dig6 = host_agc_enable;
|
||||||
|
assert re.search(
|
||||||
|
r'assign\s+gpio_dig6\s*=\s*host_agc_enable\s*;', rtl
|
||||||
|
), "gpio_dig6 must be driven by host_agc_enable (not tied low)"
|
||||||
|
# Must NOT have the old tied-low pattern
|
||||||
|
assert not re.search(
|
||||||
|
r"assign\s+gpio_dig6\s*=\s*1'b0\s*;", rtl
|
||||||
|
), "gpio_dig6 must NOT be tied low — it carries AGC enable"
|
||||||
|
|
||||||
|
def test_fpga_agc_enable_boot_default_off(self):
|
||||||
|
"""FPGA host_agc_enable must reset to 0 (AGC off at boot)."""
|
||||||
|
v_defaults = cp.parse_verilog_reset_defaults()
|
||||||
|
assert "host_agc_enable" in v_defaults, (
|
||||||
|
"host_agc_enable not found in reset block"
|
||||||
|
)
|
||||||
|
assert v_defaults["host_agc_enable"] == 0, (
|
||||||
|
f"host_agc_enable reset default is {v_defaults['host_agc_enable']}, "
|
||||||
|
"expected 0 (AGC off at boot)"
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_mcu_agc_constructor_default_off(self):
|
||||||
|
"""MCU ADAR1000_AGC constructor must default enabled=false."""
|
||||||
|
agc_cpp = (cp.MCU_LIB_DIR / "ADAR1000_AGC.cpp").read_text()
|
||||||
|
# The constructor initializer list must have enabled(false)
|
||||||
|
assert re.search(
|
||||||
|
r'enabled\s*\(\s*false\s*\)', agc_cpp
|
||||||
|
), "ADAR1000_AGC constructor must initialize enabled(false)"
|
||||||
|
assert not re.search(
|
||||||
|
r'enabled\s*\(\s*true\s*\)', agc_cpp
|
||||||
|
), "ADAR1000_AGC constructor must NOT initialize enabled(true)"
|
||||||
|
|
||||||
|
def test_mcu_reads_dig6_before_agc_gate(self):
|
||||||
|
"""MCU main loop must read DIG_6 GPIO to sync outerAgc.enabled."""
|
||||||
|
main_cpp = (cp.MCU_CODE_DIR / "main.cpp").read_text()
|
||||||
|
# DIG_6 must be read via HAL_GPIO_ReadPin
|
||||||
|
assert re.search(
|
||||||
|
r'HAL_GPIO_ReadPin\s*\(\s*FPGA_DIG6', main_cpp,
|
||||||
|
), "main.cpp must read DIG_6 GPIO via HAL_GPIO_ReadPin"
|
||||||
|
# outerAgc.enabled must be assigned from the DIG_6 reading
|
||||||
|
# (may be indirect via debounce variable like dig6_now)
|
||||||
|
assert re.search(
|
||||||
|
r'outerAgc\.enabled\s*=', main_cpp,
|
||||||
|
), "main.cpp must assign outerAgc.enabled from DIG_6 state"
|
||||||
|
|
||||||
|
def test_boot_invariant_all_layers_agc_off(self):
|
||||||
|
"""
|
||||||
|
At boot, all three layers must agree: AGC is OFF.
|
||||||
|
- FPGA: host_agc_enable resets to 0 -> DIG_6 low
|
||||||
|
- MCU: ADAR1000_AGC.enabled defaults to false
|
||||||
|
- GUI: reads status word 4 bit[11] = 0 -> reports MANUAL
|
||||||
|
"""
|
||||||
|
# FPGA
|
||||||
|
v_defaults = cp.parse_verilog_reset_defaults()
|
||||||
|
assert v_defaults.get("host_agc_enable") == 0
|
||||||
|
|
||||||
|
# MCU
|
||||||
|
agc_cpp = (cp.MCU_LIB_DIR / "ADAR1000_AGC.cpp").read_text()
|
||||||
|
assert re.search(r'enabled\s*\(\s*false\s*\)', agc_cpp)
|
||||||
|
|
||||||
|
# GUI: status word 4 bit[11] is host_agc_enable, which resets to 0.
|
||||||
|
# Verify the GUI parses bit[11] of status word 4 as the AGC flag.
|
||||||
|
gui_py = (cp.GUI_DIR / "radar_protocol.py").read_text()
|
||||||
|
assert re.search(
|
||||||
|
r'words\[4\].*>>\s*11|status_words\[4\].*>>\s*11',
|
||||||
|
gui_py,
|
||||||
|
), "GUI must parse AGC status from words[4] bit[11]"
|
||||||
|
|
||||||
|
def test_status_word4_agc_bit_matches_dig6_source(self):
|
||||||
|
"""
|
||||||
|
Status word 4 bit[11] and DIG_6 must both derive from host_agc_enable.
|
||||||
|
This guarantees the GUI status display can never lie about MCU AGC state.
|
||||||
|
"""
|
||||||
|
rtl = (cp.FPGA_DIR / "radar_system_top.v").read_text()
|
||||||
|
|
||||||
|
# DIG_6 driven by host_agc_enable
|
||||||
|
assert re.search(
|
||||||
|
r'assign\s+gpio_dig6\s*=\s*host_agc_enable\s*;', rtl
|
||||||
|
)
|
||||||
|
|
||||||
|
# Status word 4 must contain host_agc_enable (may be named
|
||||||
|
# status_agc_enable at the USB interface port boundary).
|
||||||
|
# Also verify the top-level wiring connects them.
|
||||||
|
usb_ft2232h = (cp.FPGA_DIR / "usb_data_interface_ft2232h.v").read_text()
|
||||||
|
usb_ft601 = (cp.FPGA_DIR / "usb_data_interface.v").read_text()
|
||||||
|
|
||||||
|
# USB interfaces use the port name status_agc_enable
|
||||||
|
found_in_ft2232h = "status_agc_enable" in usb_ft2232h
|
||||||
|
found_in_ft601 = "status_agc_enable" in usb_ft601
|
||||||
|
|
||||||
|
assert found_in_ft2232h or found_in_ft601, (
|
||||||
|
"status_agc_enable must appear in at least one USB interface's "
|
||||||
|
"status word to guarantee GUI status matches DIG_6"
|
||||||
|
)
|
||||||
|
|
||||||
|
# Verify top-level wiring: status_agc_enable port is connected
|
||||||
|
# to host_agc_enable (same signal that drives DIG_6)
|
||||||
|
assert re.search(
|
||||||
|
r'\.status_agc_enable\s*\(\s*host_agc_enable\s*\)', rtl
|
||||||
|
), (
|
||||||
|
"Top-level must wire .status_agc_enable(host_agc_enable) "
|
||||||
|
"so status word and DIG_6 derive from the same signal"
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_mcu_dig6_debounce_guards_enable_assignment(self):
|
||||||
|
"""
|
||||||
|
MCU must apply a 2-frame confirmation debounce before mutating
|
||||||
|
outerAgc.enabled from DIG_6 reads. A naive assignment straight from
|
||||||
|
the latest GPIO sample would let a single-cycle glitch flip the AGC
|
||||||
|
state for one frame — defeating the debounce claim in the PR body.
|
||||||
|
"""
|
||||||
|
main_cpp = (cp.MCU_CODE_DIR / "main.cpp").read_text()
|
||||||
|
|
||||||
|
# (1) Current-frame DIG_6 sample must be captured in a local variable
|
||||||
|
# so it can be compared against the previous-frame value.
|
||||||
|
now_match = re.search(
|
||||||
|
r'(bool|int|uint8_t)\s+(\w*dig6\w*)\s*=\s*[^;]*?'
|
||||||
|
r'HAL_GPIO_ReadPin\s*\(\s*FPGA_DIG6[^;]*;',
|
||||||
|
main_cpp,
|
||||||
|
re.DOTALL,
|
||||||
|
)
|
||||||
|
assert now_match, (
|
||||||
|
"DIG_6 read must be stored in a local variable (e.g. `dig6_now`) "
|
||||||
|
"so the current sample can be compared against the previous frame"
|
||||||
|
)
|
||||||
|
now_var = now_match.group(2)
|
||||||
|
|
||||||
|
# (2) Previous-frame state must persist across iterations via static
|
||||||
|
# storage, and must default to false (matches FPGA boot: AGC off).
|
||||||
|
prev_match = re.search(
|
||||||
|
r'static\s+(bool|int|uint8_t)\s+(\w*dig6\w*)\s*=\s*(false|0)\s*;',
|
||||||
|
main_cpp,
|
||||||
|
)
|
||||||
|
assert prev_match, (
|
||||||
|
"A static previous-frame variable (e.g. "
|
||||||
|
"`static bool dig6_prev = false;`) must exist, initialized to "
|
||||||
|
"false so the debounce starts in sync with the FPGA boot default"
|
||||||
|
)
|
||||||
|
prev_var = prev_match.group(2)
|
||||||
|
assert prev_var != now_var, (
|
||||||
|
f"Current and previous DIG_6 variables must be distinct "
|
||||||
|
f"(both are '{now_var}')"
|
||||||
|
)
|
||||||
|
|
||||||
|
# (3) outerAgc.enabled assignment must be gated by now == prev.
|
||||||
|
guarded_assign = re.search(
|
||||||
|
rf'if\s*\(\s*{now_var}\s*==\s*{prev_var}\s*\)\s*\{{[^}}]*?'
|
||||||
|
rf'outerAgc\.enabled\s*=\s*{now_var}\s*;',
|
||||||
|
main_cpp,
|
||||||
|
re.DOTALL,
|
||||||
|
)
|
||||||
|
assert guarded_assign, (
|
||||||
|
f"`outerAgc.enabled = {now_var};` must be inside "
|
||||||
|
f"`if ({now_var} == {prev_var}) {{ ... }}` — the confirmation "
|
||||||
|
"guard that absorbs single-sample GPIO glitches. A naive "
|
||||||
|
"assignment without this guard reintroduces the glitch bug."
|
||||||
|
)
|
||||||
|
|
||||||
|
# (4) Previous-frame variable must advance each frame.
|
||||||
|
prev_update = re.search(
|
||||||
|
rf'{prev_var}\s*=\s*{now_var}\s*;',
|
||||||
|
main_cpp,
|
||||||
|
)
|
||||||
|
assert prev_update, (
|
||||||
|
f"`{prev_var} = {now_var};` must run each frame so the "
|
||||||
|
"debounce window slides forward; without it the guard is "
|
||||||
|
"stuck and enable changes never confirm"
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
# ===================================================================
|
||||||
|
# ADAR1000 channel→register round-trip invariant (issue #90)
|
||||||
|
# ===================================================================
|
||||||
|
#
|
||||||
|
# Ground-truth invariant crossing three system layers:
|
||||||
|
# Chip (datasheet) -> Driver (MCU helpers) -> Application (callers).
|
||||||
|
#
|
||||||
|
# For every logical element ch in {0,1,2,3} (hardware channels CH1..CH4),
|
||||||
|
# the round-trip
|
||||||
|
# caller_expr(ch) --> helper_offset(channel) * stride --> base + off
|
||||||
|
# must land on the physical register REG_CH{ch+1}_* defined in the ADI
|
||||||
|
# ADAR1000 register map parsed from ADAR1000_Manager.h.
|
||||||
|
#
|
||||||
|
# Catches:
|
||||||
|
# * #90 channel rotation regardless of which side is fixed (caller OR helper).
|
||||||
|
# * Wrong stride (e.g. phase written with stride 1 instead of 2).
|
||||||
|
# * Bad mask (e.g. `channel & 0x07`, `channel & 0x01`).
|
||||||
|
# * Wrong base register in a helper.
|
||||||
|
# * New setter added with mismatched convention.
|
||||||
|
# * Caller moved to a file the test no longer scans (fails loudly).
|
||||||
|
#
|
||||||
|
# Cannot be defeated by:
|
||||||
|
# * Renaming/refactoring helper layout: the setter coverage test
|
||||||
|
# (`test_helper_sites_exist_for_all_setters`) catches missing parse.
|
||||||
|
# * Changing 0x03 to 3 or adding a named constant: the offset is
|
||||||
|
# evaluated symbolically via AST, not matched by regex.
|
||||||
|
|
||||||
|
|
||||||
|
def _parse_adar_register_map(header_text):
|
||||||
|
"""Extract `#define REG_CHn_(RX|TX)_(GAIN|PHS_I|PHS_Q)` values."""
|
||||||
|
regs = {}
|
||||||
|
for m in re.finditer(
|
||||||
|
r"^#define\s+(REG_CH[1-4]_(?:RX|TX)_(?:GAIN|PHS_I|PHS_Q))\s+(0x[0-9A-Fa-f]+)",
|
||||||
|
header_text,
|
||||||
|
re.MULTILINE,
|
||||||
|
):
|
||||||
|
regs[m.group(1)] = int(m.group(2), 16)
|
||||||
|
return regs
|
||||||
|
|
||||||
|
|
||||||
|
def _safe_eval_int_expr(expr, **variables):
|
||||||
|
"""
|
||||||
|
Evaluate a small integer expression with +, -, *, &, |, ^, ~, <<, >>.
|
||||||
|
Python's & / | / ^ / ~ / << / >> have the same semantics as C for the
|
||||||
|
operand widths we care about here (uint8_t after the mask makes the
|
||||||
|
result fit in 0..3). No floating point, no function calls, no names
|
||||||
|
outside ``variables``.
|
||||||
|
|
||||||
|
SECURITY: ``expr`` MUST come from a trusted source -- specifically,
|
||||||
|
C/C++ source text under version control in this repository (e.g.
|
||||||
|
arguments parsed out of ``main.cpp``/``ADAR1000_AGC.cpp``). Although
|
||||||
|
the AST whitelist below rejects function calls, attribute access,
|
||||||
|
subscripts, and any name not in ``variables``, ``eval`` is still
|
||||||
|
invoked on the compiled tree. Do NOT pass user-supplied / network /
|
||||||
|
GUI input here.
|
||||||
|
"""
|
||||||
|
tree = ast.parse(expr, mode="eval")
|
||||||
|
allowed = (
|
||||||
|
ast.Expression, ast.BinOp, ast.UnaryOp, ast.Constant,
|
||||||
|
ast.Name, ast.Load,
|
||||||
|
ast.Add, ast.Sub, ast.Mult, ast.Mod, ast.FloorDiv,
|
||||||
|
ast.BitAnd, ast.BitOr, ast.BitXor,
|
||||||
|
ast.USub, ast.UAdd, ast.Invert,
|
||||||
|
ast.LShift, ast.RShift,
|
||||||
|
)
|
||||||
|
for node in ast.walk(tree):
|
||||||
|
if not isinstance(node, allowed):
|
||||||
|
raise ValueError(
|
||||||
|
f"disallowed AST node {type(node).__name__!s} in `{expr}`"
|
||||||
|
)
|
||||||
|
return eval(
|
||||||
|
compile(tree, "<expr>", "eval"),
|
||||||
|
{"__builtins__": {}},
|
||||||
|
variables,
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def _extract_adar_helper_sites(manager_cpp, setter_names):
|
||||||
|
"""
|
||||||
|
For each setter, locate the body of ``void ADAR1000Manager::<setter>``
|
||||||
|
and return a list of (setter, base_register, offset_expr_c, stride)
|
||||||
|
for every ``REG_CHn_XXX + <expr>`` memory-address assignment.
|
||||||
|
"""
|
||||||
|
sites = []
|
||||||
|
for setter in setter_names:
|
||||||
|
m = re.search(
|
||||||
|
rf"void\s+ADAR1000Manager::{setter}\s*\([^)]*\)\s*\{{(.+?)^\}}",
|
||||||
|
manager_cpp,
|
||||||
|
re.MULTILINE | re.DOTALL,
|
||||||
|
)
|
||||||
|
if not m:
|
||||||
|
continue
|
||||||
|
body = m.group(1)
|
||||||
|
for access in re.finditer(
|
||||||
|
r"=\s*(REG_CH[1-4]_(?:RX|TX)_(?:GAIN|PHS_I|PHS_Q))\s*\+\s*([^;]+);",
|
||||||
|
body,
|
||||||
|
):
|
||||||
|
base = access.group(1)
|
||||||
|
rhs = access.group(2).strip()
|
||||||
|
# Trailing `* <integer>` = stride multiplier (2 for phase I/Q).
|
||||||
|
stride_match = re.match(r"(.+?)\s*\*\s*(\d+)\s*$", rhs)
|
||||||
|
if stride_match:
|
||||||
|
offset_expr = stride_match.group(1).strip()
|
||||||
|
stride = int(stride_match.group(2))
|
||||||
|
else:
|
||||||
|
offset_expr = rhs
|
||||||
|
stride = 1
|
||||||
|
sites.append((setter, base, offset_expr, stride))
|
||||||
|
return sites
|
||||||
|
|
||||||
|
|
||||||
|
# Method-definition line pattern: `[qualifier...] <ret-type> <Class>::<setter>(`
|
||||||
|
# Covers: plain `void X::f(`, `inline void X::f(`, `static bool X::f(`, etc.
|
||||||
|
_DEFN_RE = re.compile(
|
||||||
|
r"^\s*(?:inline\s+|static\s+|virtual\s+|constexpr\s+|explicit\s+)*"
|
||||||
|
r"(?:void|bool|uint\w+|int\w*|auto)\s+\S+::\w+\s*\("
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def _extract_adar_caller_sites(sources, setter):
|
||||||
|
"""
|
||||||
|
Find every call ``<obj>.<setter>(dev, <channel_expr>, ...)`` across
|
||||||
|
``sources = [(filename, text), ...]``. Returns (filename, line_no,
|
||||||
|
channel_expr) for each. Skips function declarations/definitions.
|
||||||
|
|
||||||
|
Arg list up to matching `)`: restricted to a single line. All existing
|
||||||
|
call sites fit on one line; a future multi-line refactor would drop
|
||||||
|
callers from the scan, which the round-trip test surfaces loudly via
|
||||||
|
`assert callers` (rather than silently missing a site).
|
||||||
|
"""
|
||||||
|
out = []
|
||||||
|
call_re = re.compile(rf"\b{setter}\s*\(([^;]*?)\)\s*;")
|
||||||
|
for filename, text in sources:
|
||||||
|
for line_no, line in enumerate(text.splitlines(), start=1):
|
||||||
|
# Skip method definition / declaration lines.
|
||||||
|
if _DEFN_RE.match(line):
|
||||||
|
continue
|
||||||
|
cm = call_re.search(line)
|
||||||
|
if not cm:
|
||||||
|
continue
|
||||||
|
args = _split_top_level_commas(cm.group(1))
|
||||||
|
if len(args) < 2:
|
||||||
|
continue
|
||||||
|
channel_expr = args[1].strip()
|
||||||
|
out.append((filename, line_no, channel_expr))
|
||||||
|
return out
|
||||||
|
|
||||||
|
|
||||||
|
def _split_top_level_commas(text):
|
||||||
|
"""Split on commas that sit at paren-depth 0 (ignores nested calls)."""
|
||||||
|
parts, depth, cur = [], 0, []
|
||||||
|
for ch in text:
|
||||||
|
if ch == "(":
|
||||||
|
depth += 1
|
||||||
|
cur.append(ch)
|
||||||
|
elif ch == ")":
|
||||||
|
depth -= 1
|
||||||
|
cur.append(ch)
|
||||||
|
elif ch == "," and depth == 0:
|
||||||
|
parts.append("".join(cur))
|
||||||
|
cur = []
|
||||||
|
else:
|
||||||
|
cur.append(ch)
|
||||||
|
if cur:
|
||||||
|
parts.append("".join(cur))
|
||||||
|
return parts
|
||||||
|
|
||||||
|
|
||||||
|
class TestTier1Adar1000ChannelRegisterRoundTrip:
|
||||||
|
"""
|
||||||
|
Cross-layer round-trip: caller channel expr -> helper offset formula
|
||||||
|
-> physical register address must equal REG_CH{ch+1}_* for every
|
||||||
|
caller and every ch in {0,1,2,3}.
|
||||||
|
|
||||||
|
See module-level block comment above and upstream issue #90.
|
||||||
|
"""
|
||||||
|
|
||||||
|
_SETTERS = (
|
||||||
|
"adarSetRxPhase",
|
||||||
|
"adarSetTxPhase",
|
||||||
|
"adarSetRxVgaGain",
|
||||||
|
"adarSetTxVgaGain",
|
||||||
|
)
|
||||||
|
|
||||||
|
# Register base -> stride override. Parsed values of stride are
|
||||||
|
# trusted; this table is the independent ground truth for cross-check.
|
||||||
|
_EXPECTED_STRIDE: ClassVar[dict[str, int]] = {
|
||||||
|
"REG_CH1_RX_GAIN": 1,
|
||||||
|
"REG_CH1_TX_GAIN": 1,
|
||||||
|
"REG_CH1_RX_PHS_I": 2,
|
||||||
|
"REG_CH1_RX_PHS_Q": 2,
|
||||||
|
"REG_CH1_TX_PHS_I": 2,
|
||||||
|
"REG_CH1_TX_PHS_Q": 2,
|
||||||
|
}
|
||||||
|
|
||||||
|
@classmethod
|
||||||
|
def setup_class(cls):
|
||||||
|
cls.header_txt = (cp.MCU_LIB_DIR / "ADAR1000_Manager.h").read_text()
|
||||||
|
cls.manager_txt = (cp.MCU_LIB_DIR / "ADAR1000_Manager.cpp").read_text()
|
||||||
|
cls.reg_map = _parse_adar_register_map(cls.header_txt)
|
||||||
|
cls.helper_sites = _extract_adar_helper_sites(
|
||||||
|
cls.manager_txt, cls._SETTERS,
|
||||||
|
)
|
||||||
|
# Auto-discover every C++ TU under the MCU tree so a new caller
|
||||||
|
# added to e.g. a future ``ADAR1000_Calibration.cpp`` cannot
|
||||||
|
# silently escape the round-trip check (issue #90 reviewer note).
|
||||||
|
# Exclude any path containing a ``tests`` segment so this test
|
||||||
|
# does not parse its own fixtures. The resulting list is
|
||||||
|
# deterministic (sorted) for reproducible parametrization.
|
||||||
|
scanned = []
|
||||||
|
seen = set()
|
||||||
|
for root in (cp.MCU_LIB_DIR, cp.MCU_CODE_DIR):
|
||||||
|
for path in sorted(root.rglob("*.cpp")):
|
||||||
|
if "tests" in path.parts:
|
||||||
|
continue
|
||||||
|
if path in seen:
|
||||||
|
continue
|
||||||
|
seen.add(path)
|
||||||
|
scanned.append((path.name, path.read_text()))
|
||||||
|
cls.sources = scanned
|
||||||
|
# Sanity: the two TUs known to call ADAR1000 setters at the time
|
||||||
|
# of issue #90 must be in scope. If a future refactor renames or
|
||||||
|
# moves them this assert fires loudly rather than silently
|
||||||
|
# passing an empty round-trip.
|
||||||
|
scanned_names = {n for (n, _) in scanned}
|
||||||
|
for required in ("ADAR1000_AGC.cpp", "main.cpp", "ADAR1000_Manager.cpp"):
|
||||||
|
assert required in scanned_names, (
|
||||||
|
f"Auto-discovery missed `{required}`; check MCU_LIB_DIR / "
|
||||||
|
f"MCU_CODE_DIR roots in contract_parser.py."
|
||||||
|
)
|
||||||
|
|
||||||
|
# ---------- Tier A: chip ground truth ----------------------------
|
||||||
|
|
||||||
|
def test_register_map_gain_stride_is_one_per_channel(self):
|
||||||
|
"""Datasheet invariant: RX/TX VGA gain registers are 1 byte apart."""
|
||||||
|
for kind in ("RX_GAIN", "TX_GAIN"):
|
||||||
|
for n in range(1, 4):
|
||||||
|
delta = (
|
||||||
|
self.reg_map[f"REG_CH{n+1}_{kind}"]
|
||||||
|
- self.reg_map[f"REG_CH{n}_{kind}"]
|
||||||
|
)
|
||||||
|
assert delta == 1, (
|
||||||
|
f"ADAR1000 register map invariant broken: "
|
||||||
|
f"REG_CH{n+1}_{kind} - REG_CH{n}_{kind} = {delta}, "
|
||||||
|
f"datasheet says 1. Either the header was mis-edited "
|
||||||
|
f"or ADI released a part with a different map."
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_register_map_phase_stride_is_two_per_channel(self):
|
||||||
|
"""Datasheet invariant: phase I/Q pairs occupy 2 bytes per channel."""
|
||||||
|
for kind in ("RX_PHS_I", "RX_PHS_Q", "TX_PHS_I", "TX_PHS_Q"):
|
||||||
|
for n in range(1, 4):
|
||||||
|
delta = (
|
||||||
|
self.reg_map[f"REG_CH{n+1}_{kind}"]
|
||||||
|
- self.reg_map[f"REG_CH{n}_{kind}"]
|
||||||
|
)
|
||||||
|
assert delta == 2, (
|
||||||
|
f"ADAR1000 register map invariant broken: "
|
||||||
|
f"REG_CH{n+1}_{kind} - REG_CH{n}_{kind} = {delta}, "
|
||||||
|
f"datasheet says 2."
|
||||||
|
)
|
||||||
|
|
||||||
|
# ---------- Tier B: driver parses cleanly -------------------------
|
||||||
|
|
||||||
|
def test_helper_sites_exist_for_all_setters(self):
|
||||||
|
"""Every channel-indexed setter must parse at least one register access."""
|
||||||
|
found = {s for (s, _, _, _) in self.helper_sites}
|
||||||
|
missing = set(self._SETTERS) - found
|
||||||
|
assert not missing, (
|
||||||
|
f"Helper parse failed for: {sorted(missing)}. "
|
||||||
|
f"Either a setter was renamed (update _SETTERS), moved out of "
|
||||||
|
f"ADAR1000_Manager.cpp (extend scan scope), or the register-"
|
||||||
|
f"access form changed beyond `REG_CHn_XXX + <expr>`. "
|
||||||
|
f"DO NOT weaken this test without reviewing issue #90."
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_helper_parsed_stride_matches_datasheet(self):
|
||||||
|
"""Parsed helper strides must match the datasheet register spacing."""
|
||||||
|
for setter, base, offset_expr, stride in self.helper_sites:
|
||||||
|
expected = self._EXPECTED_STRIDE.get(base)
|
||||||
|
assert expected is not None, (
|
||||||
|
f"{setter} writes to unrecognised base `{base}`. "
|
||||||
|
f"If ADI added a new channel-indexed register block, "
|
||||||
|
f"extend _EXPECTED_STRIDE with its datasheet stride."
|
||||||
|
)
|
||||||
|
assert stride == expected, (
|
||||||
|
f"{setter} helper uses stride {stride} for `{base}` "
|
||||||
|
f"(`{offset_expr} * {stride}`), datasheet says {expected}. "
|
||||||
|
f"Writes will overlap or skip channels."
|
||||||
|
)
|
||||||
|
|
||||||
|
# ---------- Tier C: round-trip to physical register ---------------
|
||||||
|
|
||||||
|
def test_all_callers_pass_one_based_channel(self):
|
||||||
|
"""
|
||||||
|
INVARIANT: every caller's channel argument must, for ch in
|
||||||
|
{0,1,2,3}, evaluate to a 1-based ADI channel index in {1,2,3,4}.
|
||||||
|
|
||||||
|
The bug fixed in #90 was that helpers used ``channel & 0x03``
|
||||||
|
directly, so a caller passing bare ``ch`` (0..3) appeared to
|
||||||
|
work for ch=0..2 and silently aliased ch=3 onto CH4-then-CH1.
|
||||||
|
After the fix, helpers do ``(channel - 1) & 0x03`` and reject
|
||||||
|
``channel < 1 || channel > 4``. A future caller written as
|
||||||
|
``adarSetRxPhase(dev, ch, ...)`` (bare 0-based) or
|
||||||
|
``adarSetRxPhase(dev, 0, ...)`` (literal 0) would silently be
|
||||||
|
dropped by the bounds-check at runtime; this test catches it at
|
||||||
|
CI time instead.
|
||||||
|
|
||||||
|
The check intentionally lives one tier above the round-trip test
|
||||||
|
so the failure message points the reader at the API contract
|
||||||
|
(1-based per ADI datasheet & ADAR1000_AGC.cpp:76) rather than at
|
||||||
|
a register-arithmetic mismatch.
|
||||||
|
"""
|
||||||
|
offenders = []
|
||||||
|
for setter in self._SETTERS:
|
||||||
|
callers = _extract_adar_caller_sites(self.sources, setter)
|
||||||
|
for filename, line_no, ch_expr in callers:
|
||||||
|
for ch in range(4):
|
||||||
|
try:
|
||||||
|
channel_val = _safe_eval_int_expr(ch_expr, ch=ch)
|
||||||
|
except (NameError, KeyError, ValueError) as e:
|
||||||
|
offenders.append(
|
||||||
|
f" - {filename}:{line_no} {setter}("
|
||||||
|
f"…, `{ch_expr}`, …) -- ch={ch}: "
|
||||||
|
f"unparseable ({e})"
|
||||||
|
)
|
||||||
|
continue
|
||||||
|
if channel_val not in (1, 2, 3, 4):
|
||||||
|
offenders.append(
|
||||||
|
f" - {filename}:{line_no} {setter}("
|
||||||
|
f"…, `{ch_expr}`, …) -- ch={ch}: "
|
||||||
|
f"channel={channel_val}, expected 1..4"
|
||||||
|
)
|
||||||
|
assert not offenders, (
|
||||||
|
"ADAR1000 1-based channel API contract violated. The fix "
|
||||||
|
"for issue #90 requires every caller to pass channel in "
|
||||||
|
"{1,2,3,4} (CH1..CH4 per ADI datasheet). Bare 0-based ch "
|
||||||
|
"or a literal 0 will be silently dropped by the helper's "
|
||||||
|
"bounds check. Offenders:\n" + "\n".join(offenders)
|
||||||
|
)
|
||||||
|
|
||||||
|
@pytest.mark.parametrize(
|
||||||
|
"setter",
|
||||||
|
[
|
||||||
|
"adarSetRxPhase",
|
||||||
|
"adarSetTxPhase",
|
||||||
|
"adarSetRxVgaGain",
|
||||||
|
"adarSetTxVgaGain",
|
||||||
|
],
|
||||||
|
)
|
||||||
|
def test_round_trip_lands_on_intended_physical_channel(self, setter):
|
||||||
|
"""
|
||||||
|
INVARIANT: for every caller of ``<setter>`` and every logical ch
|
||||||
|
in {0,1,2,3}, the effective register address equals
|
||||||
|
REG_CH{ch+1}_*. Catches #90 regardless of fix direction.
|
||||||
|
"""
|
||||||
|
callers = _extract_adar_caller_sites(self.sources, setter)
|
||||||
|
assert callers, (
|
||||||
|
f"No callers of `{setter}` found. Either the test scope is "
|
||||||
|
f"incomplete (extend `setup_class.sources`) or the symbol was "
|
||||||
|
f"inlined/removed. A blind test is a dangerous test — "
|
||||||
|
f"investigate before weakening."
|
||||||
|
)
|
||||||
|
helpers = [
|
||||||
|
(b, e, s) for (nm, b, e, s) in self.helper_sites if nm == setter
|
||||||
|
]
|
||||||
|
assert helpers, f"helper body for `{setter}` not parseable"
|
||||||
|
|
||||||
|
errors = []
|
||||||
|
for filename, line_no, ch_expr in callers:
|
||||||
|
for ch in range(4):
|
||||||
|
try:
|
||||||
|
channel_val = _safe_eval_int_expr(ch_expr, ch=ch)
|
||||||
|
except (NameError, KeyError, ValueError) as e:
|
||||||
|
pytest.fail(
|
||||||
|
f"{filename}:{line_no}: caller channel expression "
|
||||||
|
f"`{ch_expr}` uses symbol outside {{ch}} or a "
|
||||||
|
f"disallowed operator ({e}). Extend "
|
||||||
|
f"_safe_eval_int_expr variables or rewrite the "
|
||||||
|
f"call site with a supported expression."
|
||||||
|
)
|
||||||
|
for base_sym, offset_expr, stride in helpers:
|
||||||
|
try:
|
||||||
|
offset = _safe_eval_int_expr(
|
||||||
|
offset_expr, channel=channel_val,
|
||||||
|
)
|
||||||
|
except (NameError, KeyError, ValueError) as e:
|
||||||
|
pytest.fail(
|
||||||
|
f"helper `{setter}` offset expr "
|
||||||
|
f"`{offset_expr}` uses symbol outside "
|
||||||
|
f"{{channel}} or a disallowed operator ({e}). "
|
||||||
|
f"Extend _safe_eval_int_expr variables if new "
|
||||||
|
f"driver state is introduced."
|
||||||
|
)
|
||||||
|
final = self.reg_map[base_sym] + offset * stride
|
||||||
|
expected_sym = base_sym.replace("CH1", f"CH{ch + 1}")
|
||||||
|
expected = self.reg_map[expected_sym]
|
||||||
|
if final != expected:
|
||||||
|
errors.append(
|
||||||
|
f" - {filename}:{line_no} {setter} "
|
||||||
|
f"caller `{ch_expr}` | ch={ch} -> "
|
||||||
|
f"channel={channel_val} -> "
|
||||||
|
f"`{base_sym} + ({offset_expr})"
|
||||||
|
f"{' * ' + str(stride) if stride != 1 else ''}`"
|
||||||
|
f" = 0x{final:03X} "
|
||||||
|
f"(expected {expected_sym} = 0x{expected:03X})"
|
||||||
|
)
|
||||||
|
assert not errors, (
|
||||||
|
f"ADAR1000 channel round-trip FAILED for {setter} "
|
||||||
|
f"({len(errors)} mismatches) — writes routed to wrong physical "
|
||||||
|
f"channel. This is issue #90.\n" + "\n".join(errors)
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
class TestTier1DataPacketLayout:
|
class TestTier1DataPacketLayout:
|
||||||
"""Verify data packet byte layout matches between Python and Verilog."""
|
"""Verify data packet byte layout matches between Python and Verilog."""
|
||||||
|
|
||||||
@@ -468,6 +1154,204 @@ class TestTier1STM32SettingsPacket:
|
|||||||
assert flag == [23, 46, 158, 237], f"Start flag: {flag}"
|
assert flag == [23, 46, 158, 237], f"Start flag: {flag}"
|
||||||
|
|
||||||
|
|
||||||
|
# ===================================================================
|
||||||
|
# TIER 2: ADAR1000 Vector Modulator Lookup-Table Ground Truth
|
||||||
|
# ===================================================================
|
||||||
|
#
|
||||||
|
# Cross-layer contract: the firmware constants
|
||||||
|
# ADAR1000Manager::VM_I[128] / VM_Q[128]
|
||||||
|
# (in 9_Firmware/9_1_Microcontroller/9_1_1_C_Cpp_Libraries/ADAR1000_Manager.cpp)
|
||||||
|
# MUST equal the byte values published in the ADAR1000 datasheet Rev. B,
|
||||||
|
# Tables 13-16 page 34 ("Phase Shifter Programming"), on a uniform 2.8125 deg
|
||||||
|
# grid (index N == phase N * 360/128 deg).
|
||||||
|
#
|
||||||
|
# Independent ground truth lives in tools/verify_adar1000_vm_tables.py
|
||||||
|
# (transcribed from the datasheet, cross-checked against the ADI Linux
|
||||||
|
# beamformer driver as a secondary source). This test imports that
|
||||||
|
# reference and asserts a byte-exact match.
|
||||||
|
#
|
||||||
|
# Historical bug guarded against: from initial commit through PR #94 the
|
||||||
|
# arrays shipped as empty placeholders ("// ... (same as in your original
|
||||||
|
# file)"), so every adarSetRxPhase / adarSetTxPhase call wrote I=Q=0 and
|
||||||
|
# beam steering was non-functional. A separate VM_GAIN[128] table was
|
||||||
|
# declared but never read anywhere; this test also enforces its removal so
|
||||||
|
# it cannot be reintroduced and silently shadow real bugs.
|
||||||
|
|
||||||
|
class TestTier2Adar1000VmTableGroundTruth:
|
||||||
|
"""Firmware ADAR1000 VM_I/VM_Q must match datasheet ground truth byte-exact."""
|
||||||
|
|
||||||
|
@pytest.fixture(scope="class")
|
||||||
|
def cpp_source(self):
|
||||||
|
path = (
|
||||||
|
cp.REPO_ROOT
|
||||||
|
/ "9_Firmware"
|
||||||
|
/ "9_1_Microcontroller"
|
||||||
|
/ "9_1_1_C_Cpp_Libraries"
|
||||||
|
/ "ADAR1000_Manager.cpp"
|
||||||
|
)
|
||||||
|
assert path.is_file(), f"Firmware source missing: {path}"
|
||||||
|
return path.read_text()
|
||||||
|
|
||||||
|
def test_ground_truth_table_shape(self):
|
||||||
|
"""Sanity-check the imported reference (defends against import-path mishap)."""
|
||||||
|
gt = adar_vm.GROUND_TRUTH
|
||||||
|
assert len(gt) == 128, "Ground-truth table must have exactly 128 entries"
|
||||||
|
# Each row is (deg_int, deg_frac_e4, vm_i_byte, vm_q_byte)
|
||||||
|
for k, row in enumerate(gt):
|
||||||
|
assert len(row) == 4, f"Row {k} malformed: {row}"
|
||||||
|
assert 0 <= row[2] <= 0xFF, f"VM_I[{k}] out of byte range: {row[2]:#x}"
|
||||||
|
assert 0 <= row[3] <= 0xFF, f"VM_Q[{k}] out of byte range: {row[3]:#x}"
|
||||||
|
# Byte format: bits[7:6] reserved zero, bits[5] polarity, bits[4:0] mag
|
||||||
|
assert (row[2] & 0xC0) == 0, f"VM_I[{k}] reserved bits set: {row[2]:#x}"
|
||||||
|
assert (row[3] & 0xC0) == 0, f"VM_Q[{k}] reserved bits set: {row[3]:#x}"
|
||||||
|
|
||||||
|
def test_ground_truth_byte_format(self):
|
||||||
|
"""Transcription self-check: every VM_I/VM_Q byte has reserved bits clear."""
|
||||||
|
errors = adar_vm.check_byte_format("VM_I_REF", adar_vm.VM_I_REF)
|
||||||
|
errors += adar_vm.check_byte_format("VM_Q_REF", adar_vm.VM_Q_REF)
|
||||||
|
assert not errors, (
|
||||||
|
"Byte-format violations in embedded GROUND_TRUTH (likely transcription "
|
||||||
|
"typo from ADAR1000 datasheet Tables 13-16):\n " + "\n ".join(errors)
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_ground_truth_uniform_2p8125_deg_grid(self):
|
||||||
|
"""Transcription self-check: angles form a uniform 2.8125 deg grid.
|
||||||
|
|
||||||
|
This is the assumption that lets the firmware use `VM_*[phase % 128]`
|
||||||
|
as a direct index (no nearest-neighbour search). If the embedded
|
||||||
|
angles drift off the grid, the firmware's indexing model is wrong.
|
||||||
|
"""
|
||||||
|
errors = adar_vm.check_uniform_2p8125_deg_step()
|
||||||
|
assert not errors, (
|
||||||
|
"Non-uniform angle grid in GROUND_TRUTH:\n " + "\n ".join(errors)
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_ground_truth_quadrant_symmetry(self):
|
||||||
|
"""Transcription self-check: phi and phi+180 deg have same magnitude,
|
||||||
|
opposite polarity. Catches swapped/rotated rows in the table.
|
||||||
|
"""
|
||||||
|
errors = adar_vm.check_quadrant_symmetry()
|
||||||
|
assert not errors, (
|
||||||
|
"Quadrant-symmetry violation in GROUND_TRUTH (table rows may be "
|
||||||
|
"transposed or mis-transcribed):\n " + "\n ".join(errors)
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_ground_truth_cardinal_points(self):
|
||||||
|
"""Transcription self-check: the four cardinal phases (0, 90, 180,
|
||||||
|
270 deg) match the datasheet-published extrema exactly.
|
||||||
|
"""
|
||||||
|
errors = adar_vm.check_cardinal_points()
|
||||||
|
assert not errors, (
|
||||||
|
"Cardinal-point mismatch in GROUND_TRUTH vs ADAR1000 datasheet "
|
||||||
|
"Tables 13-16:\n " + "\n ".join(errors)
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_firmware_vm_i_matches_datasheet(self, cpp_source):
|
||||||
|
gt = adar_vm.GROUND_TRUTH
|
||||||
|
firmware = adar_vm.parse_array(cpp_source, "VM_I")
|
||||||
|
assert firmware is not None, (
|
||||||
|
"Could not parse VM_I[128] from ADAR1000_Manager.cpp; "
|
||||||
|
"definition pattern may have drifted"
|
||||||
|
)
|
||||||
|
assert len(firmware) == 128, (
|
||||||
|
f"VM_I has {len(firmware)} entries, expected 128. "
|
||||||
|
"Empty placeholder regression — every phase write would emit I=0 "
|
||||||
|
"and beam steering would be silently broken."
|
||||||
|
)
|
||||||
|
mismatches = [
|
||||||
|
(k, firmware[k], gt[k][2])
|
||||||
|
for k in range(128)
|
||||||
|
if firmware[k] != gt[k][2]
|
||||||
|
]
|
||||||
|
assert not mismatches, (
|
||||||
|
f"VM_I diverges from datasheet at {len(mismatches)} indices; "
|
||||||
|
f"first 5: {mismatches[:5]}"
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_firmware_vm_q_matches_datasheet(self, cpp_source):
|
||||||
|
gt = adar_vm.GROUND_TRUTH
|
||||||
|
firmware = adar_vm.parse_array(cpp_source, "VM_Q")
|
||||||
|
assert firmware is not None, (
|
||||||
|
"Could not parse VM_Q[128] from ADAR1000_Manager.cpp; "
|
||||||
|
"definition pattern may have drifted"
|
||||||
|
)
|
||||||
|
assert len(firmware) == 128, (
|
||||||
|
f"VM_Q has {len(firmware)} entries, expected 128. "
|
||||||
|
"Empty placeholder regression — every phase write would emit Q=0."
|
||||||
|
)
|
||||||
|
mismatches = [
|
||||||
|
(k, firmware[k], gt[k][3])
|
||||||
|
for k in range(128)
|
||||||
|
if firmware[k] != gt[k][3]
|
||||||
|
]
|
||||||
|
assert not mismatches, (
|
||||||
|
f"VM_Q diverges from datasheet at {len(mismatches)} indices; "
|
||||||
|
f"first 5: {mismatches[:5]}"
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_vm_gain_table_is_not_reintroduced(self, cpp_source):
|
||||||
|
"""Dead-code regression guard: VM_GAIN[128] must not exist as code.
|
||||||
|
|
||||||
|
The ADAR1000 vector modulator has no separate gain register; magnitude
|
||||||
|
is bits[4:0] of the I/Q bytes themselves. Per-channel VGA gain uses
|
||||||
|
registers CHx_RX_GAIN (0x10-0x13) / CHx_TX_GAIN (0x1C-0x1F) written
|
||||||
|
directly by adarSetRxVgaGain / adarSetTxVgaGain. A VM_GAIN[] array
|
||||||
|
was declared in early development, never populated, never read, and
|
||||||
|
was removed in PR fix/adar1000-vm-tables. Reintroducing it would
|
||||||
|
suggest (falsely) that an extra lookup is needed and could mask the
|
||||||
|
real signal path.
|
||||||
|
|
||||||
|
Uses a tokenising comment/string stripper so that the historical
|
||||||
|
explanation comment in the cpp file, as well as any string literal
|
||||||
|
containing the substring "VM_GAIN", does not trip the check.
|
||||||
|
"""
|
||||||
|
stripped = _strip_cxx_comments_and_strings(cpp_source)
|
||||||
|
assert "VM_GAIN" not in stripped, (
|
||||||
|
"VM_GAIN symbol reappeared in ADAR1000_Manager.cpp executable code. "
|
||||||
|
"This array has no hardware backing and must not be reintroduced. "
|
||||||
|
"If you need to scale phase-state magnitude, modify VM_I/VM_Q "
|
||||||
|
"bits[4:0] directly per the datasheet."
|
||||||
|
)
|
||||||
|
|
||||||
|
def test_adversarial_corruption_is_detected(self):
|
||||||
|
"""Adversarial self-test: a flipped byte in firmware MUST fail comparison.
|
||||||
|
|
||||||
|
Defends against silent bypass — e.g. a future refactor that mocks
|
||||||
|
parse_array() or compares len() only. We synthesise a corrupted cpp
|
||||||
|
source string, run the same parser, and assert mismatch is detected.
|
||||||
|
"""
|
||||||
|
gt = adar_vm.GROUND_TRUTH
|
||||||
|
# Build a minimal valid-looking cpp snippet with one corrupted byte.
|
||||||
|
good_i = ", ".join(f"0x{gt[k][2]:02X}" for k in range(128))
|
||||||
|
good_q = ", ".join(f"0x{gt[k][3]:02X}" for k in range(128))
|
||||||
|
snippet_good = (
|
||||||
|
f"const uint8_t ADAR1000Manager::VM_I[128] = {{ {good_i} }};\n"
|
||||||
|
f"const uint8_t ADAR1000Manager::VM_Q[128] = {{ {good_q} }};\n"
|
||||||
|
)
|
||||||
|
# Sanity: the unmodified snippet must parse and match.
|
||||||
|
parsed_i = adar_vm.parse_array(snippet_good, "VM_I")
|
||||||
|
assert parsed_i is not None and len(parsed_i) == 128
|
||||||
|
assert all(parsed_i[k] == gt[k][2] for k in range(128)), (
|
||||||
|
"Self-test setup error: golden snippet does not match GROUND_TRUTH"
|
||||||
|
)
|
||||||
|
# Now flip the low bit of VM_I[42] and confirm detection.
|
||||||
|
corrupted_byte = gt[42][2] ^ 0x01
|
||||||
|
bad_i = ", ".join(
|
||||||
|
f"0x{(corrupted_byte if k == 42 else gt[k][2]):02X}"
|
||||||
|
for k in range(128)
|
||||||
|
)
|
||||||
|
snippet_bad = (
|
||||||
|
f"const uint8_t ADAR1000Manager::VM_I[128] = {{ {bad_i} }};\n"
|
||||||
|
f"const uint8_t ADAR1000Manager::VM_Q[128] = {{ {good_q} }};\n"
|
||||||
|
)
|
||||||
|
parsed_bad = adar_vm.parse_array(snippet_bad, "VM_I")
|
||||||
|
assert parsed_bad is not None and len(parsed_bad) == 128
|
||||||
|
assert parsed_bad[42] != gt[42][2], (
|
||||||
|
"Adversarial self-test FAILED: corrupted byte at index 42 was "
|
||||||
|
"not detected by parse_array. The cross-layer test is bypassable."
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
# ===================================================================
|
# ===================================================================
|
||||||
# TIER 2: Verilog Cosimulation
|
# TIER 2: Verilog Cosimulation
|
||||||
# ===================================================================
|
# ===================================================================
|
||||||
|
|||||||
+3
-3
@@ -78,9 +78,9 @@ Every test binary must exit 0.
|
|||||||
|
|
||||||
```bash
|
```bash
|
||||||
cd 9_Firmware/9_3_GUI
|
cd 9_Firmware/9_3_GUI
|
||||||
python3 -m pytest test_radar_dashboard.py -v
|
python3 -m pytest test_GUI_V65_Tk.py -v
|
||||||
# or without pytest:
|
# or without pytest:
|
||||||
python3 -m unittest test_radar_dashboard -v
|
python3 -m unittest test_GUI_V65_Tk -v
|
||||||
```
|
```
|
||||||
|
|
||||||
57+ protocol and rendering tests. The `test_record_and_stop` test
|
57+ protocol and rendering tests. The `test_record_and_stop` test
|
||||||
@@ -130,7 +130,7 @@ Before pushing, confirm:
|
|||||||
|
|
||||||
1. `bash run_regression.sh` — all phases pass
|
1. `bash run_regression.sh` — all phases pass
|
||||||
2. `make all` (MCU tests) — 20/20 pass
|
2. `make all` (MCU tests) — 20/20 pass
|
||||||
3. `python3 -m unittest test_radar_dashboard -v` — all pass
|
3. `python3 -m unittest test_GUI_V65_Tk -v` — all pass
|
||||||
4. `python3 validate_mem_files.py` — all checks pass
|
4. `python3 validate_mem_files.py` — all checks pass
|
||||||
5. `python3 compare.py dc && python3 compare_doppler.py stationary && python3 compare_mf.py all`
|
5. `python3 compare.py dc && python3 compare_doppler.py stationary && python3 compare_mf.py all`
|
||||||
6. `git diff --check` — no whitespace issues
|
6. `git diff --check` — no whitespace issues
|
||||||
|
|||||||
@@ -68,13 +68,13 @@ The AERIS-10 main sub-systems are:
|
|||||||
- Clock Generator (AD9523-1)
|
- Clock Generator (AD9523-1)
|
||||||
- 2x Frequency Synthesizers (ADF4382)
|
- 2x Frequency Synthesizers (ADF4382)
|
||||||
- 4x 4-Channel Phase Shifters (ADAR1000) for RADAR pulse sequencing
|
- 4x 4-Channel Phase Shifters (ADAR1000) for RADAR pulse sequencing
|
||||||
- 2x ADS7830 ADCs (on Power Amplifier Boards) for Idq measurement
|
- 2x ADS7830 8-channel I²C ADCs (Main Board, U88 @ 0x48 / U89 @ 0x4A) for 16x Idq measurement, one per PA channel, each sensed through a 5 mΩ shunt on the PA board and an INA241A3 current-sense amplifier (x50) on the Main Board
|
||||||
- 2x DAC5578 (on Power Amplifier Boards) for Vg control
|
- 2x DAC5578 8-channel I²C DACs (Main Board, U7 @ 0x48 / U69 @ 0x49) for 16x Vg control, one per PA channel; closed-loop calibrated at boot to the target Idq
|
||||||
- GPS module for GUI map centering
|
- GPS module (UM982) for GUI map centering and per-detection position tagging
|
||||||
- GY-85 IMU for pitch/roll correction of target coordinates
|
- GY-85 IMU for pitch/roll correction of target coordinates
|
||||||
- BMP180 Barometer
|
- BMP180 Barometer
|
||||||
- Stepper Motor
|
- Stepper Motor
|
||||||
- 8x ADS7830 Temperature Sensors for cooling fan control
|
- 1x ADS7830 8-channel I²C ADC (Main Board, U10) reading 8 thermistors for thermal monitoring; a single GPIO (EN_DIS_COOLING) switches the cooling fans on when any channel exceeds the threshold
|
||||||
- RF switches
|
- RF switches
|
||||||
|
|
||||||
- **16x Power Amplifier Boards** - Used only for AERIS-10E version, featuring 10Watt QPA2962 GaN amplifier for extended range
|
- **16x Power Amplifier Boards** - Used only for AERIS-10E version, featuring 10Watt QPA2962 GaN amplifier for extended range
|
||||||
|
|||||||
Reference in New Issue
Block a user