From 7c15c33af48ee37d904bd9b6947b0e7b1d324030 Mon Sep 17 00:00:00 2001 From: Oliver Lok Trevor Date: Fri, 9 Feb 2024 22:08:00 -0500 Subject: [PATCH 01/79] Big Dish control is working! Updated with MIT location. --- config/config.yaml | 48 +- config/schema.yaml | 2 +- radio/radio_process/radio_process.grc | 469 ++++++++++- radio/radio_process/radioonly.grc | 465 ++++++++++- .../radio_process/radio_process.py | 727 ++++-------------- srt/daemon/rotor_control/bigdish_client.py | 58 ++ srt/daemon/rotor_control/motors.py | 43 ++ srt/daemon/rotor_control/rotors.py | 5 +- 8 files changed, 1223 insertions(+), 594 deletions(-) create mode 100755 srt/daemon/rotor_control/bigdish_client.py diff --git a/config/config.yaml b/config/config.yaml index edf7a303..cf7f9dc5 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -1,49 +1,49 @@ SOFTWARE: Small Radio Telescope STATION: - latitude: 42.5 - longitude: -71.5 - name: Haystack + latitude: 42.360236 + longitude: -71.089694 + name: W1XM EMERGENCY_CONTACT: - name: John Doe - email: test@example.com - phone_number: 555-555-5555 + name: Oliver Trevor + email: olt@mit.edu + phone_number: 925-367-3607 AZLIMITS: - lower_bound: 38.0 - upper_bound: 355.0 + lower_bound: 0.0 + upper_bound: 360.0 ELLIMITS: lower_bound: 0.0 - upper_bound: 89.0 + upper_bound: 85.0 STOW_LOCATION: - azimuth: 38.0 - elevation: 0.0 + azimuth: 60.0 + elevation: 30.0 CAL_LOCATION: - azimuth: 120.0 - elevation: 7.0 + azimuth: 270.0 + elevation: 50.0 HORIZON_POINTS: - azimuth: 0 elevation: 0 - azimuth: 120 - elevation: 5 + elevation: 0 - azimuth: 240 - elevation: 5 + elevation: 0 - azimuth: 360 elevation: 0 -MOTOR_TYPE: NONE -MOTOR_PORT: /dev/ttyUSB0 -MOTOR_BAUDRATE: 600 +MOTOR_TYPE: W1XMBIGDISH +MOTOR_PORT: None +MOTOR_BAUDRATE: 0 RADIO_CF: 1420000000 -RADIO_SF: 2400000 -RADIO_FREQ_CORR: -50000 +RADIO_SF: 2000000 +RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 256 -RADIO_INTEG_CYCLES: 100000 +RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 25 BEAMWIDTH: 7.0 -TSYS: 171 -TCAL: 290 +TSYS: 60 +TCAL: 40 SAVE_DIRECTORY: ~/Desktop/SRT-Saves RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 3000 +DASHBOARD_REFRESH_MS: 1000 diff --git a/config/schema.yaml b/config/schema.yaml index 779ad0d9..17ebcfd2 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -6,7 +6,7 @@ ELLIMITS: include('limit') STOW_LOCATION: include('az_el_point') CAL_LOCATION: include('az_el_point') HORIZON_POINTS: list(include('az_el_point'), min=0) -MOTOR_TYPE: enum('ALFASPID', 'H180MOUNT', 'PUSHROD', 'NONE') +MOTOR_TYPE: enum('ALFASPID', 'H180MOUNT', 'PUSHROD', 'NONE', 'W1XMBIGDISH') MOTOR_BAUDRATE: int() MOTOR_PORT: str() RADIO_CF: int() diff --git a/radio/radio_process/radio_process.grc b/radio/radio_process/radio_process.grc index 8ae67250..355838ac 100644 --- a/radio/radio_process/radio_process.grc +++ b/radio/radio_process/radio_process.grc @@ -165,11 +165,35 @@ blocks: coordinate: [100, 268] rotation: 0 state: true +- name: rf_freq + id: variable + parameters: + comment: '' + value: freq + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [984, 12.0] + rotation: 0 + state: enabled +- name: rf_gain + id: variable + parameters: + comment: '' + value: '20' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [896, 12.0] + rotation: 0 + state: enabled - name: samp_rate id: variable parameters: comment: '' - value: '2400000' + value: '2000000' states: bus_sink: false bus_source: false @@ -1157,7 +1181,443 @@ blocks: bus_sink: false bus_source: false bus_structure: null - coordinate: [293, 99] + coordinate: [296, 92.0] + rotation: 0 + state: disabled +- name: uhd_usrp_source_1 + id: uhd_usrp_source + parameters: + affinity: '' + alias: '' + ant0: '"RX2"' + ant1: '"RX2"' + ant10: '"RX2"' + ant11: '"RX2"' + ant12: '"RX2"' + ant13: '"RX2"' + ant14: '"RX2"' + ant15: '"RX2"' + ant16: '"RX2"' + ant17: '"RX2"' + ant18: '"RX2"' + ant19: '"RX2"' + ant2: '"RX2"' + ant20: '"RX2"' + ant21: '"RX2"' + ant22: '"RX2"' + ant23: '"RX2"' + ant24: '"RX2"' + ant25: '"RX2"' + ant26: '"RX2"' + ant27: '"RX2"' + ant28: '"RX2"' + ant29: '"RX2"' + ant3: '"RX2"' + ant30: '"RX2"' + ant31: '"RX2"' + ant4: '"RX2"' + ant5: '"RX2"' + ant6: '"RX2"' + ant7: '"RX2"' + ant8: '"RX2"' + ant9: '"RX2"' + bw0: samp_rate + bw1: '0' + bw10: '0' + bw11: '0' + bw12: '0' + bw13: '0' + bw14: '0' + bw15: '0' + bw16: '0' + bw17: '0' + bw18: '0' + bw19: '0' + bw2: '0' + bw20: '0' + bw21: '0' + bw22: '0' + bw23: '0' + bw24: '0' + bw25: '0' + bw26: '0' + bw27: '0' + bw28: '0' + bw29: '0' + bw3: '0' + bw30: '0' + bw31: '0' + bw4: '0' + bw5: '0' + bw6: '0' + bw7: '0' + bw8: '0' + bw9: '0' + center_freq0: rf_freq + center_freq1: '0' + center_freq10: '0' + center_freq11: '0' + center_freq12: '0' + center_freq13: '0' + center_freq14: '0' + center_freq15: '0' + center_freq16: '0' + center_freq17: '0' + center_freq18: '0' + center_freq19: '0' + center_freq2: '0' + center_freq20: '0' + center_freq21: '0' + center_freq22: '0' + center_freq23: '0' + center_freq24: '0' + center_freq25: '0' + center_freq26: '0' + center_freq27: '0' + center_freq28: '0' + center_freq29: '0' + center_freq3: '0' + center_freq30: '0' + center_freq31: '0' + center_freq4: '0' + center_freq5: '0' + center_freq6: '0' + center_freq7: '0' + center_freq8: '0' + center_freq9: '0' + clock_rate: 0e0 + clock_source0: '' + clock_source1: '' + clock_source2: '' + clock_source3: '' + clock_source4: '' + clock_source5: '' + clock_source6: '' + clock_source7: '' + comment: '' + dc_offs0: 0+0j + dc_offs1: 0+0j + dc_offs10: 0+0j + dc_offs11: 0+0j + dc_offs12: 0+0j + dc_offs13: 0+0j + dc_offs14: 0+0j + dc_offs15: 0+0j + dc_offs16: 0+0j + dc_offs17: 0+0j + dc_offs18: 0+0j + dc_offs19: 0+0j + dc_offs2: 0+0j + dc_offs20: 0+0j + dc_offs21: 0+0j + dc_offs22: 0+0j + dc_offs23: 0+0j + dc_offs24: 0+0j + dc_offs25: 0+0j + dc_offs26: 0+0j + dc_offs27: 0+0j + dc_offs28: 0+0j + dc_offs29: 0+0j + dc_offs3: 0+0j + dc_offs30: 0+0j + dc_offs31: 0+0j + dc_offs4: 0+0j + dc_offs5: 0+0j + dc_offs6: 0+0j + dc_offs7: 0+0j + dc_offs8: 0+0j + dc_offs9: 0+0j + dc_offs_enb0: auto + dc_offs_enb1: default + dc_offs_enb10: default + dc_offs_enb11: default + dc_offs_enb12: default + dc_offs_enb13: default + dc_offs_enb14: default + dc_offs_enb15: default + dc_offs_enb16: default + dc_offs_enb17: default + dc_offs_enb18: default + dc_offs_enb19: default + dc_offs_enb2: default + dc_offs_enb20: default + dc_offs_enb21: default + dc_offs_enb22: default + dc_offs_enb23: default + dc_offs_enb24: default + dc_offs_enb25: default + dc_offs_enb26: default + dc_offs_enb27: default + dc_offs_enb28: default + dc_offs_enb29: default + dc_offs_enb3: default + dc_offs_enb30: default + dc_offs_enb31: default + dc_offs_enb4: default + dc_offs_enb5: default + dc_offs_enb6: default + dc_offs_enb7: default + dc_offs_enb8: default + dc_offs_enb9: default + dev_addr: '"addr=172.25.14.11"' + dev_args: '' + gain0: rf_gain + gain1: '0' + gain10: '0' + gain11: '0' + gain12: '0' + gain13: '0' + gain14: '0' + gain15: '0' + gain16: '0' + gain17: '0' + gain18: '0' + gain19: '0' + gain2: '0' + gain20: '0' + gain21: '0' + gain22: '0' + gain23: '0' + gain24: '0' + gain25: '0' + gain26: '0' + gain27: '0' + gain28: '0' + gain29: '0' + gain3: '0' + gain30: '0' + gain31: '0' + gain4: '0' + gain5: '0' + gain6: '0' + gain7: '0' + gain8: '0' + gain9: '0' + gain_type0: default + gain_type1: default + gain_type10: default + gain_type11: default + gain_type12: default + gain_type13: default + gain_type14: default + gain_type15: default + gain_type16: default + gain_type17: default + gain_type18: default + gain_type19: default + gain_type2: default + gain_type20: default + gain_type21: default + gain_type22: default + gain_type23: default + gain_type24: default + gain_type25: default + gain_type26: default + gain_type27: default + gain_type28: default + gain_type29: default + gain_type3: default + gain_type30: default + gain_type31: default + gain_type4: default + gain_type5: default + gain_type6: default + gain_type7: default + gain_type8: default + gain_type9: default + iq_imbal0: 0+0j + iq_imbal1: 0+0j + iq_imbal10: 0+0j + iq_imbal11: 0+0j + iq_imbal12: 0+0j + iq_imbal13: 0+0j + iq_imbal14: 0+0j + iq_imbal15: 0+0j + iq_imbal16: 0+0j + iq_imbal17: 0+0j + iq_imbal18: 0+0j + iq_imbal19: 0+0j + iq_imbal2: 0+0j + iq_imbal20: 0+0j + iq_imbal21: 0+0j + iq_imbal22: 0+0j + iq_imbal23: 0+0j + iq_imbal24: 0+0j + iq_imbal25: 0+0j + iq_imbal26: 0+0j + iq_imbal27: 0+0j + iq_imbal28: 0+0j + iq_imbal29: 0+0j + iq_imbal3: 0+0j + iq_imbal30: 0+0j + iq_imbal31: 0+0j + iq_imbal4: 0+0j + iq_imbal5: 0+0j + iq_imbal6: 0+0j + iq_imbal7: 0+0j + iq_imbal8: 0+0j + iq_imbal9: 0+0j + iq_imbal_enb0: auto + iq_imbal_enb1: default + iq_imbal_enb10: default + iq_imbal_enb11: default + iq_imbal_enb12: default + iq_imbal_enb13: default + iq_imbal_enb14: default + iq_imbal_enb15: default + iq_imbal_enb16: default + iq_imbal_enb17: default + iq_imbal_enb18: default + iq_imbal_enb19: default + iq_imbal_enb2: default + iq_imbal_enb20: default + iq_imbal_enb21: default + iq_imbal_enb22: default + iq_imbal_enb23: default + iq_imbal_enb24: default + iq_imbal_enb25: default + iq_imbal_enb26: default + iq_imbal_enb27: default + iq_imbal_enb28: default + iq_imbal_enb29: default + iq_imbal_enb3: default + iq_imbal_enb30: default + iq_imbal_enb31: default + iq_imbal_enb4: default + iq_imbal_enb5: default + iq_imbal_enb6: default + iq_imbal_enb7: default + iq_imbal_enb8: default + iq_imbal_enb9: default + lo_export0: 'False' + lo_export1: 'False' + lo_export10: 'False' + lo_export11: 'False' + lo_export12: 'False' + lo_export13: 'False' + lo_export14: 'False' + lo_export15: 'False' + lo_export16: 'False' + lo_export17: 'False' + lo_export18: 'False' + lo_export19: 'False' + lo_export2: 'False' + lo_export20: 'False' + lo_export21: 'False' + lo_export22: 'False' + lo_export23: 'False' + lo_export24: 'False' + lo_export25: 'False' + lo_export26: 'False' + lo_export27: 'False' + lo_export28: 'False' + lo_export29: 'False' + lo_export3: 'False' + lo_export30: 'False' + lo_export31: 'False' + lo_export4: 'False' + lo_export5: 'False' + lo_export6: 'False' + lo_export7: 'False' + lo_export8: 'False' + lo_export9: 'False' + lo_source0: internal + lo_source1: internal + lo_source10: internal + lo_source11: internal + lo_source12: internal + lo_source13: internal + lo_source14: internal + lo_source15: internal + lo_source16: internal + lo_source17: internal + lo_source18: internal + lo_source19: internal + lo_source2: internal + lo_source20: internal + lo_source21: internal + lo_source22: internal + lo_source23: internal + lo_source24: internal + lo_source25: internal + lo_source26: internal + lo_source27: internal + lo_source28: internal + lo_source29: internal + lo_source3: internal + lo_source30: internal + lo_source31: internal + lo_source4: internal + lo_source5: internal + lo_source6: internal + lo_source7: internal + lo_source8: internal + lo_source9: internal + maxoutbuf: '0' + minoutbuf: '0' + nchan: '1' + num_mboards: '1' + otw: '' + rx_agc0: Default + rx_agc1: Default + rx_agc10: Default + rx_agc11: Default + rx_agc12: Default + rx_agc13: Default + rx_agc14: Default + rx_agc15: Default + rx_agc16: Default + rx_agc17: Default + rx_agc18: Default + rx_agc19: Default + rx_agc2: Default + rx_agc20: Default + rx_agc21: Default + rx_agc22: Default + rx_agc23: Default + rx_agc24: Default + rx_agc25: Default + rx_agc26: Default + rx_agc27: Default + rx_agc28: Default + rx_agc29: Default + rx_agc3: Default + rx_agc30: Default + rx_agc31: Default + rx_agc4: Default + rx_agc5: Default + rx_agc6: Default + rx_agc7: Default + rx_agc8: Default + rx_agc9: Default + samp_rate: samp_rate + sd_spec0: '' + sd_spec1: '' + sd_spec2: '' + sd_spec3: '' + sd_spec4: '' + sd_spec5: '' + sd_spec6: '' + sd_spec7: '' + show_lo_controls: 'False' + start_time: '-1.0' + stream_args: '' + stream_chans: '[]' + sync: pc_clock_next_pps + time_source0: '' + time_source1: '' + time_source2: '' + time_source3: '' + time_source4: '' + time_source5: '' + time_source6: '' + time_source7: '' + type: fc32 + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [328, 108.0] rotation: 0 state: true - name: xmlrpc_server_0 @@ -1171,7 +1631,7 @@ blocks: bus_sink: false bus_source: false bus_structure: null - coordinate: [935, 52] + coordinate: [1016, 84.0] rotation: 0 state: true - name: zeromq_pub_sink_0 @@ -1335,7 +1795,8 @@ connections: - [dc_blocker_xx_0, '0', blocks_skiphead_0, '0'] - [fft_vxx_0, '0', blocks_complex_to_mag_squared_0, '0'] - [osmosdr_source_0, '0', add_clock_tags, '0'] +- [uhd_usrp_source_1, '0', add_clock_tags, '0'] metadata: file_format: 1 - grc_version: 3.10.5.1 + grc_version: 3.10.5.0 diff --git a/radio/radio_process/radioonly.grc b/radio/radio_process/radioonly.grc index 0d27718d..3486591e 100644 --- a/radio/radio_process/radioonly.grc +++ b/radio/radio_process/radioonly.grc @@ -165,6 +165,30 @@ blocks: coordinate: [132, 282] rotation: 0 state: true +- name: rf_freq + id: variable + parameters: + comment: '' + value: freq + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [1080, 60.0] + rotation: 0 + state: enabled +- name: rf_gain + id: variable + parameters: + comment: '' + value: '20' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [1000, 60.0] + rotation: 0 + state: enabled - name: samp_rate id: variable parameters: @@ -1042,7 +1066,7 @@ blocks: bus_structure: null coordinate: [432, 172.0] rotation: 0 - state: true + state: disabled - name: qtgui_sink_x_0 id: qtgui_sink_x parameters: @@ -1294,6 +1318,442 @@ blocks: coordinate: [904, 836.0] rotation: 0 state: true +- name: usrp0 + id: uhd_usrp_source + parameters: + affinity: '' + alias: usrp0 + ant0: '"RX2"' + ant1: '"RX2"' + ant10: '"RX2"' + ant11: '"RX2"' + ant12: '"RX2"' + ant13: '"RX2"' + ant14: '"RX2"' + ant15: '"RX2"' + ant16: '"RX2"' + ant17: '"RX2"' + ant18: '"RX2"' + ant19: '"RX2"' + ant2: '"RX2"' + ant20: '"RX2"' + ant21: '"RX2"' + ant22: '"RX2"' + ant23: '"RX2"' + ant24: '"RX2"' + ant25: '"RX2"' + ant26: '"RX2"' + ant27: '"RX2"' + ant28: '"RX2"' + ant29: '"RX2"' + ant3: '"RX2"' + ant30: '"RX2"' + ant31: '"RX2"' + ant4: '"RX2"' + ant5: '"RX2"' + ant6: '"RX2"' + ant7: '"RX2"' + ant8: '"RX2"' + ant9: '"RX2"' + bw0: samp_rate + bw1: samp_rate + bw10: '0' + bw11: '0' + bw12: '0' + bw13: '0' + bw14: '0' + bw15: '0' + bw16: '0' + bw17: '0' + bw18: '0' + bw19: '0' + bw2: '0' + bw20: '0' + bw21: '0' + bw22: '0' + bw23: '0' + bw24: '0' + bw25: '0' + bw26: '0' + bw27: '0' + bw28: '0' + bw29: '0' + bw3: '0' + bw30: '0' + bw31: '0' + bw4: '0' + bw5: '0' + bw6: '0' + bw7: '0' + bw8: '0' + bw9: '0' + center_freq0: freq + center_freq1: freq + center_freq10: '0' + center_freq11: '0' + center_freq12: '0' + center_freq13: '0' + center_freq14: '0' + center_freq15: '0' + center_freq16: '0' + center_freq17: '0' + center_freq18: '0' + center_freq19: '0' + center_freq2: rf_freq + center_freq20: '0' + center_freq21: '0' + center_freq22: '0' + center_freq23: '0' + center_freq24: '0' + center_freq25: '0' + center_freq26: '0' + center_freq27: '0' + center_freq28: '0' + center_freq29: '0' + center_freq3: rf_freq + center_freq30: '0' + center_freq31: '0' + center_freq4: '0' + center_freq5: '0' + center_freq6: '0' + center_freq7: '0' + center_freq8: '0' + center_freq9: '0' + clock_rate: 0e0 + clock_source0: '' + clock_source1: '' + clock_source2: '' + clock_source3: '' + clock_source4: '' + clock_source5: '' + clock_source6: '' + clock_source7: '' + comment: '' + dc_offs0: 0+0j + dc_offs1: 0+0j + dc_offs10: 0+0j + dc_offs11: 0+0j + dc_offs12: 0+0j + dc_offs13: 0+0j + dc_offs14: 0+0j + dc_offs15: 0+0j + dc_offs16: 0+0j + dc_offs17: 0+0j + dc_offs18: 0+0j + dc_offs19: 0+0j + dc_offs2: 0+0j + dc_offs20: 0+0j + dc_offs21: 0+0j + dc_offs22: 0+0j + dc_offs23: 0+0j + dc_offs24: 0+0j + dc_offs25: 0+0j + dc_offs26: 0+0j + dc_offs27: 0+0j + dc_offs28: 0+0j + dc_offs29: 0+0j + dc_offs3: 0+0j + dc_offs30: 0+0j + dc_offs31: 0+0j + dc_offs4: 0+0j + dc_offs5: 0+0j + dc_offs6: 0+0j + dc_offs7: 0+0j + dc_offs8: 0+0j + dc_offs9: 0+0j + dc_offs_enb0: default + dc_offs_enb1: default + dc_offs_enb10: default + dc_offs_enb11: default + dc_offs_enb12: default + dc_offs_enb13: default + dc_offs_enb14: default + dc_offs_enb15: default + dc_offs_enb16: default + dc_offs_enb17: default + dc_offs_enb18: default + dc_offs_enb19: default + dc_offs_enb2: default + dc_offs_enb20: default + dc_offs_enb21: default + dc_offs_enb22: default + dc_offs_enb23: default + dc_offs_enb24: default + dc_offs_enb25: default + dc_offs_enb26: default + dc_offs_enb27: default + dc_offs_enb28: default + dc_offs_enb29: default + dc_offs_enb3: default + dc_offs_enb30: default + dc_offs_enb31: default + dc_offs_enb4: default + dc_offs_enb5: default + dc_offs_enb6: default + dc_offs_enb7: default + dc_offs_enb8: default + dc_offs_enb9: default + dev_addr: '"addr=172.25.14.11"' + dev_args: '' + gain0: rf_gain + gain1: rf_gain + gain10: '0' + gain11: '0' + gain12: '0' + gain13: '0' + gain14: '0' + gain15: '0' + gain16: '0' + gain17: '0' + gain18: '0' + gain19: '0' + gain2: rf_gain + gain20: '0' + gain21: '0' + gain22: '0' + gain23: '0' + gain24: '0' + gain25: '0' + gain26: '0' + gain27: '0' + gain28: '0' + gain29: '0' + gain3: rf_gain + gain30: '0' + gain31: '0' + gain4: '0' + gain5: '0' + gain6: '0' + gain7: '0' + gain8: '0' + gain9: '0' + gain_type0: default + gain_type1: default + gain_type10: default + gain_type11: default + gain_type12: default + gain_type13: default + gain_type14: default + gain_type15: default + gain_type16: default + gain_type17: default + gain_type18: default + gain_type19: default + gain_type2: default + gain_type20: default + gain_type21: default + gain_type22: default + gain_type23: default + gain_type24: default + gain_type25: default + gain_type26: default + gain_type27: default + gain_type28: default + gain_type29: default + gain_type3: default + gain_type30: default + gain_type31: default + gain_type4: default + gain_type5: default + gain_type6: default + gain_type7: default + gain_type8: default + gain_type9: default + iq_imbal0: 0+0j + iq_imbal1: 0+0j + iq_imbal10: 0+0j + iq_imbal11: 0+0j + iq_imbal12: 0+0j + iq_imbal13: 0+0j + iq_imbal14: 0+0j + iq_imbal15: 0+0j + iq_imbal16: 0+0j + iq_imbal17: 0+0j + iq_imbal18: 0+0j + iq_imbal19: 0+0j + iq_imbal2: 0+0j + iq_imbal20: 0+0j + iq_imbal21: 0+0j + iq_imbal22: 0+0j + iq_imbal23: 0+0j + iq_imbal24: 0+0j + iq_imbal25: 0+0j + iq_imbal26: 0+0j + iq_imbal27: 0+0j + iq_imbal28: 0+0j + iq_imbal29: 0+0j + iq_imbal3: 0+0j + iq_imbal30: 0+0j + iq_imbal31: 0+0j + iq_imbal4: 0+0j + iq_imbal5: 0+0j + iq_imbal6: 0+0j + iq_imbal7: 0+0j + iq_imbal8: 0+0j + iq_imbal9: 0+0j + iq_imbal_enb0: default + iq_imbal_enb1: default + iq_imbal_enb10: default + iq_imbal_enb11: default + iq_imbal_enb12: default + iq_imbal_enb13: default + iq_imbal_enb14: default + iq_imbal_enb15: default + iq_imbal_enb16: default + iq_imbal_enb17: default + iq_imbal_enb18: default + iq_imbal_enb19: default + iq_imbal_enb2: default + iq_imbal_enb20: default + iq_imbal_enb21: default + iq_imbal_enb22: default + iq_imbal_enb23: default + iq_imbal_enb24: default + iq_imbal_enb25: default + iq_imbal_enb26: default + iq_imbal_enb27: default + iq_imbal_enb28: default + iq_imbal_enb29: default + iq_imbal_enb3: default + iq_imbal_enb30: default + iq_imbal_enb31: default + iq_imbal_enb4: default + iq_imbal_enb5: default + iq_imbal_enb6: default + iq_imbal_enb7: default + iq_imbal_enb8: default + iq_imbal_enb9: default + lo_export0: 'False' + lo_export1: 'False' + lo_export10: 'False' + lo_export11: 'False' + lo_export12: 'False' + lo_export13: 'False' + lo_export14: 'False' + lo_export15: 'False' + lo_export16: 'False' + lo_export17: 'False' + lo_export18: 'False' + lo_export19: 'False' + lo_export2: 'False' + lo_export20: 'False' + lo_export21: 'False' + lo_export22: 'False' + lo_export23: 'False' + lo_export24: 'False' + lo_export25: 'False' + lo_export26: 'False' + lo_export27: 'False' + lo_export28: 'False' + lo_export29: 'False' + lo_export3: 'False' + lo_export30: 'False' + lo_export31: 'False' + lo_export4: 'False' + lo_export5: 'False' + lo_export6: 'False' + lo_export7: 'False' + lo_export8: 'False' + lo_export9: 'False' + lo_source0: internal + lo_source1: internal + lo_source10: internal + lo_source11: internal + lo_source12: internal + lo_source13: internal + lo_source14: internal + lo_source15: internal + lo_source16: internal + lo_source17: internal + lo_source18: internal + lo_source19: internal + lo_source2: external + lo_source20: internal + lo_source21: internal + lo_source22: internal + lo_source23: internal + lo_source24: internal + lo_source25: internal + lo_source26: internal + lo_source27: internal + lo_source28: internal + lo_source29: internal + lo_source3: external + lo_source30: internal + lo_source31: internal + lo_source4: internal + lo_source5: internal + lo_source6: internal + lo_source7: internal + lo_source8: internal + lo_source9: internal + maxoutbuf: '0' + minoutbuf: '0' + nchan: '1' + num_mboards: '1' + otw: '' + rx_agc0: Default + rx_agc1: Default + rx_agc10: Default + rx_agc11: Default + rx_agc12: Default + rx_agc13: Default + rx_agc14: Default + rx_agc15: Default + rx_agc16: Default + rx_agc17: Default + rx_agc18: Default + rx_agc19: Default + rx_agc2: Default + rx_agc20: Default + rx_agc21: Default + rx_agc22: Default + rx_agc23: Default + rx_agc24: Default + rx_agc25: Default + rx_agc26: Default + rx_agc27: Default + rx_agc28: Default + rx_agc29: Default + rx_agc3: Default + rx_agc30: Default + rx_agc31: Default + rx_agc4: Default + rx_agc5: Default + rx_agc6: Default + rx_agc7: Default + rx_agc8: Default + rx_agc9: Default + samp_rate: samp_rate + sd_spec0: '' + sd_spec1: '' + sd_spec2: '' + sd_spec3: '' + sd_spec4: '' + sd_spec5: '' + sd_spec6: '' + sd_spec7: '' + show_lo_controls: 'False' + start_time: '-1.0' + stream_args: '' + stream_chans: '[]' + sync: pc_clock_next_pps + time_source0: '' + time_source1: '' + time_source2: '' + time_source3: '' + time_source4: '' + time_source5: '' + time_source6: '' + time_source7: '' + type: fc32 + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [456, 188.0] + rotation: 0 + state: true connections: - [blocks_add_xx_0, '0', fft_vxx_0, '0'] @@ -1322,7 +1782,8 @@ connections: - [fft_vxx_0, '0', blocks_multiply_conjugate_cc_0, '0'] - [fft_vxx_0, '0', blocks_multiply_conjugate_cc_0, '1'] - [osmosdr_source_0, '0', dc_blocker_xx_0, '0'] +- [usrp0, '0', dc_blocker_xx_0, '0'] metadata: file_format: 1 - grc_version: 3.10.5.1 + grc_version: 3.10.5.0 diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 33b5f0e1..baef75f3 100644 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -6,7 +6,7 @@ # # GNU Radio Python Flow Graph # Title: radio_process -# GNU Radio version: 3.8.1.0 +# GNU Radio version: 3.10.5.0 from gnuradio import blocks import pmt @@ -20,24 +20,24 @@ from argparse import ArgumentParser from gnuradio.eng_arg import eng_float, intx from gnuradio import eng_notation +from gnuradio import uhd +import time from gnuradio import zeromq - -try: - import SimpleXMLRPCServer -except ModuleNotFoundError: - import xmlrpc.server as SimpleXMLRPCServer - +from xmlrpc.server import SimpleXMLRPCServer import threading -from . import add_clock_tags import math import numpy as np -import osmosdr +from . import add_clock_tags +#import osmosdr import time + + class radio_process(gr.top_block): + def __init__(self, num_bins=256, num_integrations=100000): - gr.top_block.__init__(self, "radio_process") + gr.top_block.__init__(self, "radio_process", catch_exceptions=True) ################################################## # Parameters @@ -48,26 +48,25 @@ def __init__(self, num_bins=256, num_integrations=100000): ################################################## # Variables ################################################## - self.sinc_sample_locations = sinc_sample_locations = np.arange( - -np.pi * 4 / 2.0, np.pi * 4 / 2.0, np.pi / num_bins - ) - self.sinc_samples = sinc_samples = np.sinc( - sinc_sample_locations / np.pi) + + self.sinc_sample_locations = sinc_sample_locations = np.arange(-np.pi*4/2.0, np.pi*4/2.0, np.pi/num_bins) + self.sinc_samples = sinc_samples = np.sinc(sinc_sample_locations/np.pi) + self.freq = freq = 1420000000 self.vlsr = vlsr = np.nan self.tsys = tsys = 171 self.tcal = tcal = 290 - self.tag_period = tag_period = num_bins * num_integrations + self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" - self.samp_rate = samp_rate = 2400000 + self.samp_rate = samp_rate = 2000000 + self.rf_gain = rf_gain = 20 + self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan self.is_running = is_running = False self.glon = glon = np.nan self.glat = glat = np.nan - self.freq = freq = 1420000000 self.fft_window = fft_window = window.blackmanharris(num_bins) - self.custom_window = custom_window = sinc_samples * \ - np.hamming(4 * num_bins) + self.custom_window = custom_window = sinc_samples*np.hamming(4*num_bins) self.cal_values = cal_values = np.repeat(np.nan, num_bins) self.cal_pwr = cal_pwr = 1 self.beam_switch = beam_switch = 0 @@ -75,173 +74,91 @@ def __init__(self, num_bins=256, num_integrations=100000): ################################################## # Blocks ################################################## - self.zeromq_pub_sink_2_0 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5561", 100, False, -1 - ) - self.zeromq_pub_sink_2 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5560", 100, True, -1 - ) - self.zeromq_pub_sink_1_0 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5562", 100, True, -1 - ) - self.zeromq_pub_sink_1 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5563", 100, False, -1 - ) - self.zeromq_pub_sink_0_0 = zeromq.pub_sink( - gr.sizeof_gr_complex, 1, "tcp://127.0.0.1:5559", 100, False, -1 - ) - self.zeromq_pub_sink_0 = zeromq.pub_sink( - gr.sizeof_gr_complex, 1, "tcp://127.0.0.1:5558", 100, True, -1 - ) - self.xmlrpc_server_0 = SimpleXMLRPCServer.SimpleXMLRPCServer( - ("localhost", 5557), allow_none=True - ) + self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True) + self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True) + self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True) + self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True) + self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True) + self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True) + self.xmlrpc_server_0 = SimpleXMLRPCServer(('localhost', 5557), allow_none=True) self.xmlrpc_server_0.register_instance(self) - self.xmlrpc_server_0_thread = threading.Thread( - target=self.xmlrpc_server_0.serve_forever - ) + self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) self.xmlrpc_server_0_thread.daemon = True self.xmlrpc_server_0_thread.start() - self.osmosdr_source_0 = osmosdr.source( - args="numchan=" + str(1) + " " + "soapy=0" - ) - self.osmosdr_source_0.set_time_unknown_pps(osmosdr.time_spec_t()) - self.osmosdr_source_0.set_sample_rate(samp_rate) - self.osmosdr_source_0.set_center_freq(freq, 0) - self.osmosdr_source_0.set_freq_corr(0, 0) - self.osmosdr_source_0.set_gain(49, 0) - self.osmosdr_source_0.set_if_gain(0, 0) - self.osmosdr_source_0.set_bb_gain(0, 0) - self.osmosdr_source_0.set_antenna("", 0) - self.osmosdr_source_0.set_bandwidth(0, 0) - self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) - self.dc_blocker_xx_0 = filter.dc_blocker_cc( - num_bins * num_integrations, False) - self.blocks_tags_strobe_0_0 = blocks.tags_strobe( - gr.sizeof_gr_complex * 1, - pmt.to_pmt( - { - "num_bins": num_bins, - "samp_rate": samp_rate, - "num_integrations": num_integrations, - "motor_az": motor_az, - "motor_el": motor_el, - "freq": freq, - "tsys": tsys, - "tcal": tcal, - "cal_pwr": cal_pwr, - "vlsr": vlsr, - "glat": glat, - "glon": glon, - "soutrack": soutrack, - "bsw": beam_switch, - } + self.uhd_usrp_source_1 = uhd.usrp_source( + ",".join(("addr=172.25.14.11", '')), + uhd.stream_args( + cpu_format="fc32", + args='', + channels=list(range(0,1)), ), - tag_period, - pmt.intern("metadata"), - ) - self.blocks_tags_strobe_0 = blocks.tags_strobe( - gr.sizeof_gr_complex * 1, - pmt.to_pmt(float(freq)), - tag_period, - pmt.intern("rx_freq"), - ) - self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins ) - self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins - ) - self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins - ) - self.blocks_stream_to_vector_0 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins - ) - self.blocks_skiphead_0 = blocks.skiphead( - gr.sizeof_gr_complex * 1, num_bins * num_integrations - ) - self.blocks_selector_0 = blocks.selector( - gr.sizeof_gr_complex * 1, 0, 0) + + self.uhd_usrp_source_1.set_samp_rate(samp_rate) + _last_pps_time = self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() + # Poll get_time_last_pps() every 50 ms until a change is seen + while(self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() == _last_pps_time): + time.sleep(0.05) + # Set the time to PC time on next PPS + self.uhd_usrp_source_1.set_time_next_pps(uhd.time_spec(int(time.time()) + 1.0)) + # Sleep 1 second to ensure next PPS has come + time.sleep(1) + + self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) + self.uhd_usrp_source_1.set_antenna("RX2", 0) + self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) + self.uhd_usrp_source_1.set_gain(rf_gain, 0) + self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) + self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) + self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) + self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) + self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) + self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) + self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_stream_to_vector_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_skiphead_0 = blocks.skiphead(gr.sizeof_gr_complex*1, (num_bins*num_integrations)) + self.blocks_selector_0 = blocks.selector(gr.sizeof_gr_complex*1,0,0) self.blocks_selector_0.set_enabled(True) - self.blocks_multiply_const_xx_0 = blocks.multiply_const_ff( - 1.0 / float(num_integrations), num_bins - ) - self.blocks_multiply_const_vxx_1 = blocks.multiply_const_vff( - [(tsys + tcal) / (value * cal_pwr) for value in cal_values] - ) - self.blocks_multiply_const_vxx_0_0_0_0 = blocks.multiply_const_vcc( - custom_window[0:num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0 = blocks.multiply_const_vcc( - custom_window[num_bins: 2 * num_bins] - ) - self.blocks_multiply_const_vxx_0_0 = blocks.multiply_const_vcc( - custom_window[2 * num_bins: 3 * num_bins] - ) - self.blocks_multiply_const_vxx_0 = blocks.multiply_const_vcc( - custom_window[-num_bins:] - ) - self.blocks_message_strobe_0 = blocks.message_strobe( - pmt.to_pmt(is_running), 100 - ) - self.blocks_integrate_xx_0 = blocks.integrate_ff( - num_integrations, num_bins) - self.blocks_delay_0_1 = blocks.delay( - gr.sizeof_gr_complex * 1, num_bins) - self.blocks_delay_0_0 = blocks.delay( - gr.sizeof_gr_complex * 1, num_bins * 2) - self.blocks_delay_0 = blocks.delay( - gr.sizeof_gr_complex * 1, num_bins * 3) - self.blocks_complex_to_mag_squared_0 = blocks.complex_to_mag_squared( - num_bins) + self.blocks_multiply_const_xx_0 = blocks.multiply_const_ff(1.0/float(num_integrations), num_bins) + self.blocks_multiply_const_vxx_1 = blocks.multiply_const_vff([(tsys + tcal)/(value * cal_pwr) for value in cal_values]) + self.blocks_multiply_const_vxx_0_0_0_0 = blocks.multiply_const_vcc(custom_window[0:num_bins]) + self.blocks_multiply_const_vxx_0_0_0 = blocks.multiply_const_vcc(custom_window[num_bins:2*num_bins]) + self.blocks_multiply_const_vxx_0_0 = blocks.multiply_const_vcc(custom_window[2*num_bins:3*num_bins]) + self.blocks_multiply_const_vxx_0 = blocks.multiply_const_vcc(custom_window[-num_bins:]) + self.blocks_message_strobe_0 = blocks.message_strobe(pmt.to_pmt(is_running), 100) + self.blocks_integrate_xx_0 = blocks.integrate_ff(num_integrations, num_bins) + self.blocks_delay_0_1 = blocks.delay(gr.sizeof_gr_complex*1, num_bins) + self.blocks_delay_0_0 = blocks.delay(gr.sizeof_gr_complex*1, (num_bins*2)) + self.blocks_delay_0 = blocks.delay(gr.sizeof_gr_complex*1, (num_bins*3)) + self.blocks_complex_to_mag_squared_0 = blocks.complex_to_mag_squared(num_bins) self.blocks_add_xx_0_0 = blocks.add_vcc(1) self.blocks_add_xx_0 = blocks.add_vcc(num_bins) self.add_clock_tags = add_clock_tags.clk(nsamps=tag_period) + ################################################## # Connections ################################################## self.connect((self.add_clock_tags, 0), (self.blocks_add_xx_0_0, 1)) self.connect((self.blocks_add_xx_0, 0), (self.fft_vxx_0, 0)) self.connect((self.blocks_add_xx_0_0, 0), (self.blocks_selector_0, 0)) - self.connect( - (self.blocks_complex_to_mag_squared_0, - 0), (self.blocks_integrate_xx_0, 0) - ) - self.connect((self.blocks_delay_0, 0), - (self.blocks_stream_to_vector_0_2, 0)) - self.connect((self.blocks_delay_0_0, 0), - (self.blocks_stream_to_vector_0_0, 0)) - self.connect((self.blocks_delay_0_1, 0), - (self.blocks_stream_to_vector_0_1, 0)) - self.connect( - (self.blocks_integrate_xx_0, 0), (self.blocks_multiply_const_xx_0, 0) - ) - self.connect((self.blocks_multiply_const_vxx_0, 0), - (self.blocks_add_xx_0, 0)) - self.connect((self.blocks_multiply_const_vxx_0_0, 0), - (self.blocks_add_xx_0, 1)) - self.connect( - (self.blocks_multiply_const_vxx_0_0_0, 0), (self.blocks_add_xx_0, 2) - ) - self.connect( - (self.blocks_multiply_const_vxx_0_0_0_0, 0), (self.blocks_add_xx_0, 3) - ) - self.connect((self.blocks_multiply_const_vxx_1, 0), - (self.zeromq_pub_sink_1, 0)) - self.connect( - (self.blocks_multiply_const_vxx_1, 0), (self.zeromq_pub_sink_1_0, 0) - ) - self.connect( - (self.blocks_multiply_const_xx_0, - 0), (self.blocks_multiply_const_vxx_1, 0) - ) - self.connect((self.blocks_multiply_const_xx_0, 0), - (self.zeromq_pub_sink_2, 0)) - self.connect( - (self.blocks_multiply_const_xx_0, 0), (self.zeromq_pub_sink_2_0, 0) - ) + self.connect((self.blocks_complex_to_mag_squared_0, 0), (self.blocks_integrate_xx_0, 0)) + self.connect((self.blocks_delay_0, 0), (self.blocks_stream_to_vector_0_2, 0)) + self.connect((self.blocks_delay_0_0, 0), (self.blocks_stream_to_vector_0_0, 0)) + self.connect((self.blocks_delay_0_1, 0), (self.blocks_stream_to_vector_0_1, 0)) + self.connect((self.blocks_integrate_xx_0, 0), (self.blocks_multiply_const_xx_0, 0)) + self.connect((self.blocks_multiply_const_vxx_0, 0), (self.blocks_add_xx_0, 0)) + self.connect((self.blocks_multiply_const_vxx_0_0, 0), (self.blocks_add_xx_0, 1)) + self.connect((self.blocks_multiply_const_vxx_0_0_0, 0), (self.blocks_add_xx_0, 2)) + self.connect((self.blocks_multiply_const_vxx_0_0_0_0, 0), (self.blocks_add_xx_0, 3)) + self.connect((self.blocks_multiply_const_vxx_1, 0), (self.zeromq_pub_sink_1, 0)) + self.connect((self.blocks_multiply_const_vxx_1, 0), (self.zeromq_pub_sink_1_0, 0)) + self.connect((self.blocks_multiply_const_xx_0, 0), (self.blocks_multiply_const_vxx_1, 0)) + self.connect((self.blocks_multiply_const_xx_0, 0), (self.zeromq_pub_sink_2, 0)) + self.connect((self.blocks_multiply_const_xx_0, 0), (self.zeromq_pub_sink_2_0, 0)) + self.connect((self.blocks_selector_0, 0), (self.dc_blocker_xx_0, 0)) self.connect((self.blocks_selector_0, 0), (self.zeromq_pub_sink_0, 0)) self.connect((self.blocks_selector_0, 0), @@ -249,32 +166,17 @@ def __init__(self, num_bins=256, num_integrations=100000): self.connect((self.blocks_skiphead_0, 0), (self.blocks_delay_0, 0)) self.connect((self.blocks_skiphead_0, 0), (self.blocks_delay_0_0, 0)) self.connect((self.blocks_skiphead_0, 0), (self.blocks_delay_0_1, 0)) - self.connect((self.blocks_skiphead_0, 0), - (self.blocks_stream_to_vector_0, 0)) - self.connect( - (self.blocks_stream_to_vector_0, - 0), (self.blocks_multiply_const_vxx_0, 0) - ) - self.connect( - (self.blocks_stream_to_vector_0_0, 0), - (self.blocks_multiply_const_vxx_0_0_0, 0), - ) - self.connect( - (self.blocks_stream_to_vector_0_1, 0), - (self.blocks_multiply_const_vxx_0_0, 0), - ) - self.connect( - (self.blocks_stream_to_vector_0_2, 0), - (self.blocks_multiply_const_vxx_0_0_0_0, 0), - ) - self.connect((self.blocks_tags_strobe_0, 0), - (self.blocks_add_xx_0_0, 0)) - self.connect((self.blocks_tags_strobe_0_0, 0), - (self.blocks_add_xx_0_0, 2)) + self.connect((self.blocks_skiphead_0, 0), (self.blocks_stream_to_vector_0, 0)) + self.connect((self.blocks_stream_to_vector_0, 0), (self.blocks_multiply_const_vxx_0, 0)) + self.connect((self.blocks_stream_to_vector_0_0, 0), (self.blocks_multiply_const_vxx_0_0_0, 0)) + self.connect((self.blocks_stream_to_vector_0_1, 0), (self.blocks_multiply_const_vxx_0_0, 0)) + self.connect((self.blocks_stream_to_vector_0_2, 0), (self.blocks_multiply_const_vxx_0_0_0_0, 0)) + self.connect((self.blocks_tags_strobe_0, 0), (self.blocks_add_xx_0_0, 0)) + self.connect((self.blocks_tags_strobe_0_0, 0), (self.blocks_add_xx_0_0, 2)) self.connect((self.dc_blocker_xx_0, 0), (self.blocks_skiphead_0, 0)) - self.connect((self.fft_vxx_0, 0), - (self.blocks_complex_to_mag_squared_0, 0)) - self.connect((self.osmosdr_source_0, 0), (self.add_clock_tags, 0)) + self.connect((self.fft_vxx_0, 0), (self.blocks_complex_to_mag_squared_0, 0)) + self.connect((self.uhd_usrp_source_1, 0), (self.add_clock_tags, 0)) + def get_num_bins(self): return self.num_bins @@ -282,181 +184,74 @@ def get_num_bins(self): def set_num_bins(self, num_bins): self.num_bins = num_bins self.set_cal_values(np.repeat(np.nan, self.num_bins)) - self.set_custom_window(self.sinc_samples * - np.hamming(4 * self.num_bins)) + self.set_custom_window(self.sinc_samples*np.hamming(4*self.num_bins)) self.set_fft_window(window.blackmanharris(self.num_bins)) - self.set_sinc_sample_locations( - np.arange(-np.pi * 4 / 2.0, np.pi * 4 / 2.0, np.pi / self.num_bins) - ) - self.set_tag_period(self.num_bins * self.num_integrations) - self.blocks_delay_0.set_dly(self.num_bins * 3) - self.blocks_delay_0_0.set_dly(self.num_bins * 2) - self.blocks_delay_0_1.set_dly(self.num_bins) - self.blocks_multiply_const_vxx_0.set_k( - self.custom_window[-self.num_bins:]) - self.blocks_multiply_const_vxx_0_0.set_k( - self.custom_window[2 * self.num_bins: 3 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0.set_k( - self.custom_window[self.num_bins: 2 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0_0.set_k( - self.custom_window[0: self.num_bins] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.set_sinc_sample_locations(np.arange(-np.pi*4/2.0, np.pi*4/2.0, np.pi/self.num_bins)) + self.set_tag_period(self.num_bins*self.num_integrations) + self.blocks_delay_0.set_dly(int((self.num_bins*3))) + self.blocks_delay_0_0.set_dly(int((self.num_bins*2))) + self.blocks_delay_0_1.set_dly(int(self.num_bins)) + self.blocks_multiply_const_vxx_0.set_k(self.custom_window[-self.num_bins:]) + self.blocks_multiply_const_vxx_0_0.set_k(self.custom_window[2*self.num_bins:3*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + def get_num_integrations(self): return self.num_integrations def set_num_integrations(self, num_integrations): self.num_integrations = num_integrations - self.set_tag_period(self.num_bins * self.num_integrations) - self.blocks_multiply_const_xx_0.set_k( - 1.0 / float(self.num_integrations)) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.set_tag_period(self.num_bins*self.num_integrations) + self.blocks_multiply_const_xx_0.set_k(1.0/float(self.num_integrations)) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_sinc_sample_locations(self): return self.sinc_sample_locations def set_sinc_sample_locations(self, sinc_sample_locations): self.sinc_sample_locations = sinc_sample_locations - self.set_sinc_samples(np.sinc(self.sinc_sample_locations / np.pi)) + self.set_sinc_samples(np.sinc(self.sinc_sample_locations/np.pi)) def get_sinc_samples(self): return self.sinc_samples def set_sinc_samples(self, sinc_samples): self.sinc_samples = sinc_samples - self.set_custom_window(self.sinc_samples * - np.hamming(4 * self.num_bins)) + self.set_custom_window(self.sinc_samples*np.hamming(4*self.num_bins)) + + def get_freq(self): + return self.freq + + def set_freq(self, freq): + self.freq = freq + self.set_rf_freq(self.freq) + self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_vlsr(self): return self.vlsr def set_vlsr(self, vlsr): self.vlsr = vlsr - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_tsys(self): return self.tsys def set_tsys(self, tsys): self.tsys = tsys - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_tcal(self): return self.tcal def set_tcal(self, tcal): self.tcal = tcal - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_tag_period(self): return self.tag_period @@ -472,105 +267,44 @@ def get_soutrack(self): def set_soutrack(self, soutrack): self.soutrack = soutrack - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_samp_rate(self): return self.samp_rate def set_samp_rate(self, samp_rate): self.samp_rate = samp_rate - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) - self.osmosdr_source_0.set_sample_rate(self.samp_rate) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.uhd_usrp_source_1.set_samp_rate(self.samp_rate) + self.uhd_usrp_source_1.set_bandwidth(self.samp_rate, 0) + + def get_rf_gain(self): + return self.rf_gain + + def set_rf_gain(self, rf_gain): + self.rf_gain = rf_gain + self.uhd_usrp_source_1.set_gain(self.rf_gain, 0) + + def get_rf_freq(self): + return self.rf_freq + + def set_rf_freq(self, rf_freq): + self.rf_freq = rf_freq + self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) def get_motor_el(self): return self.motor_el def set_motor_el(self, motor_el): self.motor_el = motor_el - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_motor_az(self): return self.motor_az def set_motor_az(self, motor_az): self.motor_az = motor_az - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_is_running(self): return self.is_running @@ -584,80 +318,14 @@ def get_glon(self): def set_glon(self, glon): self.glon = glon - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_glat(self): return self.glat def set_glat(self, glat): self.glat = glat - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) - - def get_freq(self): - return self.freq - - def set_freq(self, freq): - self.freq = freq - self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) - self.osmosdr_source_0.set_center_freq(self.freq, 0) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_fft_window(self): return self.fft_window @@ -670,114 +338,49 @@ def get_custom_window(self): def set_custom_window(self, custom_window): self.custom_window = custom_window - self.blocks_multiply_const_vxx_0.set_k( - self.custom_window[-self.num_bins:]) - self.blocks_multiply_const_vxx_0_0.set_k( - self.custom_window[2 * self.num_bins: 3 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0.set_k( - self.custom_window[self.num_bins: 2 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0_0.set_k( - self.custom_window[0: self.num_bins] - ) + self.blocks_multiply_const_vxx_0.set_k(self.custom_window[-self.num_bins:]) + self.blocks_multiply_const_vxx_0_0.set_k(self.custom_window[2*self.num_bins:3*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) def get_cal_values(self): return self.cal_values def set_cal_values(self, cal_values): self.cal_values = cal_values - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) def get_cal_pwr(self): return self.cal_pwr def set_cal_pwr(self, cal_pwr): self.cal_pwr = cal_pwr - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_beam_switch(self): return self.beam_switch def set_beam_switch(self, beam_switch): self.beam_switch = beam_switch - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def argument_parser(): parser = ArgumentParser() parser.add_argument( - "--num-bins", - dest="num_bins", - type=intx, - default=256, - help="Set num_bins [default=%(default)r]", - ) + "--num-bins", dest="num_bins", type=intx, default=256, + help="Set num_bins [default=%(default)r]") parser.add_argument( - "--num-integrations", - dest="num_integrations", - type=intx, - default=100000, - help="Set num_integrations [default=%(default)r]", - ) + "--num-integrations", dest="num_integrations", type=intx, default=100000, + help="Set num_integrations [default=%(default)r]") return parser def main(top_block_cls=radio_process, options=None): if options is None: options = argument_parser().parse_args() - tb = top_block_cls( - num_bins=options.num_bins, num_integrations=options.num_integrations - ) + tb = top_block_cls(num_bins=options.num_bins, num_integrations=options.num_integrations) def sig_handler(sig=None, frame=None): tb.stop() @@ -793,5 +396,5 @@ def sig_handler(sig=None, frame=None): tb.wait() -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/srt/daemon/rotor_control/bigdish_client.py b/srt/daemon/rotor_control/bigdish_client.py new file mode 100755 index 00000000..149595c3 --- /dev/null +++ b/srt/daemon/rotor_control/bigdish_client.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python3 + +import time +import json +import threading +from websockets.sync.client import connect + +class BigDishClient: + def __init__(self, server_host, server_port, user, password, kick_others = False): + self.websocket = connect(f"ws://{server_host}:{server_port}") + self.message_id = 0 + self.websocket.send(json.dumps({"type": "auth", "id": self.message_id, "user": user, "password": password, "version": "0.0.1"})) + self.message_id += 1 + self.websocket.send(json.dumps({"type": "init", "id": self.message_id, "kick_others": kick_others})) + self.message_id += 1 + self.received_messages = {} + self._message_recv_thread_handle = threading.Thread(target = self._message_recv_thread) + self._message_recv_thread_handle.start() + + def _message_recv_thread(self): + for message in self.websocket: + message_decoded = json.loads(message) + self.received_messages[message_decoded["id"]] = message_decoded + + def _wait_for_response(self, id): + while True: + if id in self.received_messages: + message = self.received_messages[id] + del self.received_messages[id] + self.message_id += 1 + return message + time.sleep(0.01) + + def stow_pos(self): + self.websocket.send(json.dumps({"type": "stow_pos", "id": self.message_id})) + return self._wait_for_response(self.message_id) + + def goto_posvel_azel(self, az_pos, el_pos, az_vel, el_vel): + self.websocket.send(json.dumps({"type": "goto_posvel", "id": self.message_id, "coords": "azel", "az_pos": az_pos, "az_vel": az_vel, "el_pos": el_pos, "el_vel": el_vel})) + return self._wait_for_response(self.message_id) + + def track_radec(self, ra_pos, dec_pos, duration): + self.websocket.send(json.dumps({"type": "track", "id": self.message_id, "coords": "radec", "ra_pos": ra_pos, "dec_pos": dec_pos, "duration": duration})) + return self._wait_for_response(self.message_id) + + def track_gal(self, l_pos, b_pos, duration): + self.websocket.send(json.dumps({"type": "track", "id": self.message_id, "coords": "gal", "l_pos": l_pos, "b_pos": b_pos, "duration": duration})) + return self._wait_for_response(self.message_id) + + def get_posvel(self, coords, power): + self.websocket.send(json.dumps({"type": "get_posvel", "id": self.message_id, "coords": coords, "power": power})) + return self._wait_for_response(self.message_id) + +if __name__ == "__main__": + client = BigDishClient("localhost", 1234, "w1xm", "test", kick_others = True) + #while True: + # client.track_gal(162.592,4.5697, 5) + # time.sleep(1) diff --git a/srt/daemon/rotor_control/motors.py b/srt/daemon/rotor_control/motors.py index 24dddb0b..464959fe 100644 --- a/srt/daemon/rotor_control/motors.py +++ b/srt/daemon/rotor_control/motors.py @@ -9,6 +9,7 @@ from time import sleep from math import cos, acos, pi, sqrt, floor +from .bigdish_client import BigDishClient class Motor(ABC): """Abstract Class for All Motors Types @@ -793,3 +794,45 @@ def status(self): Current Azimuth and Elevation Coordinate as a Tuple of Floats """ return self.az, self.el + +class W1XMBigDishMotor(Motor): + """ + Class for Controlling the 54 roof Big Dish + """ + + def __init__(self): + """ + Initializer for W1XM Big Dish controller + """ + super().__init__(None, None, (0.0, 360.0), (0.0, 85.0)) + self.position = (60.0, 30.0) + self.client = BigDishClient("w1xm-radar-1.mitrs.org", 1234, "w1xm", "test", True) + + def point(self, az, el): + """Points the dish at a point + + Parameters + ---------- + az : float + Azimuth Coordinate to Point At + el : float + Elevation Coordinate to Point At + + Returns + ------- + None + """ + self.client.goto_posvel_azel(az, el, 0.0, 0.0) + self.position = (az, el) + + def status(self): + """Returns the Position of the Dish + + Returns + ------- + (float, float) + Current Azimuth and Elevation Coordinate as a Tuple of Floats + """ + pos = self.client.get_posvel("azel", False) + self.position = (pos["az_pos"], pos["el_pos"]) + return self.position diff --git a/srt/daemon/rotor_control/rotors.py b/srt/daemon/rotor_control/rotors.py index 04caaf0c..669ed69b 100644 --- a/srt/daemon/rotor_control/rotors.py +++ b/srt/daemon/rotor_control/rotors.py @@ -5,7 +5,7 @@ """ from enum import Enum -from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor +from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor, W1XMBigDishMotor def angle_within_range(angle, limits): @@ -25,6 +25,7 @@ class RotorType(Enum): ROT2 = "ALFASPID" H180 = "H180MOUNT" PUSH_ROD = "PUSHROD" + W1XM_BIG_DISH = "W1XMBIGDISH" class Rotor: @@ -58,6 +59,8 @@ def __init__(self, motor_type, port, baudrate, az_limits, el_limits): self.motor = H180Motor(port, baudrate, az_limits, el_limits) elif motor_type == RotorType.PUSH_ROD == RotorType.PUSH_ROD.value: self.motor = PushRodMotor(port, baudrate, az_limits, el_limits) + elif motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value: + self.motor = W1XMBigDishMotor() else: raise ValueError("Not a known motor type") From 6d0a067c7e63757b3c3d43c494e95c3cc60213c6 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 14 Feb 2024 01:24:41 +0000 Subject: [PATCH 02/79] Working on compatibility with big dish radar, plus bugfixes for original SRT code's tracking. changed bounds to trigger rotor position update from 0.5 degrees to 0.1 degrees. In practice this is somewhat sketchy and guarantees we average 50% of that offset over time. This should just be a periodic strobe and we should let the rotor controller decide whether or not to move. At minimum a future update should correct it to be relative to the antenna beamwidth --- config/config.yaml | 6 +++--- srt/daemon/daemon.py | 5 +++-- .../radio_control/radio_process/radio_process.py | 12 ++++++------ srt/daemon/rotor_control/motors.py | 2 +- srt/daemon/utilities/functions.py | 4 ++-- srt/dashboard/app.py | 12 +++++++----- 6 files changed, 22 insertions(+), 19 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index cf7f9dc5..703b48d3 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -34,14 +34,14 @@ MOTOR_BAUDRATE: 0 RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 -RADIO_NUM_BINS: 256 +RADIO_NUM_BINS: 512 RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 25 -BEAMWIDTH: 7.0 +BEAMWIDTH: 3.5 TSYS: 60 TCAL: 40 -SAVE_DIRECTORY: ~/Desktop/SRT-Saves +SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index d3d5dc65..8d4ca41c 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -192,8 +192,8 @@ def n_point_scan(self, object_id): scan_center = self.ephemeris_locations[object_id] np_sides = [5, 5] for scan in range(N_pnt_default): - self.log_message( - "{0} of {1} point scan.".format(scan, N_pnt_default)) + scan_center = self.ephemeris_locations[object_id] #recompute target position for every iteration + self.log_message("{0} of {1} point scan.".format(scan, N_pnt_default)) i = (scan // 5) - 2 j = (scan % 5) - 2 el_dif = i * self.beamwidth * 0.5 @@ -246,6 +246,7 @@ def beam_switch(self, object_id): rotor_loc = [] pwr_list = [] for j in range(0, 3 * self.num_beamswitches): + new_rotor_destination = self.ephemeris_locations[object_id] #recompute target position for every iteration self.radio_queue.put(("beam_switch", j + 1)) az_dif_scalar = np.cos(new_rotor_destination[1] * np.pi / 180.0) az_dif = (j % 3 - 1) * self.beamwidth / az_dif_scalar diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index baef75f3..0b670503 100644 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -28,7 +28,7 @@ import math import numpy as np from . import add_clock_tags -#import osmosdr +import osmosdr import time @@ -53,12 +53,12 @@ def __init__(self, num_bins=256, num_integrations=100000): self.sinc_samples = sinc_samples = np.sinc(sinc_sample_locations/np.pi) self.freq = freq = 1420000000 self.vlsr = vlsr = np.nan - self.tsys = tsys = 171 - self.tcal = tcal = 290 + self.tsys = tsys = 60 + self.tcal = tcal = 40 self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 - self.rf_gain = rf_gain = 20 + self.rf_gain = rf_gain = 25 self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan @@ -104,12 +104,12 @@ def __init__(self, num_bins=256, num_integrations=100000): # Sleep 1 second to ensure next PPS has come time.sleep(1) - self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) + self.uhd_usrp_source_1.set_center_freq(freq, 0) self.uhd_usrp_source_1.set_antenna("RX2", 0) self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) self.uhd_usrp_source_1.set_gain(rf_gain, 0) self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) - self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) + #self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) diff --git a/srt/daemon/rotor_control/motors.py b/srt/daemon/rotor_control/motors.py index 464959fe..36491b26 100644 --- a/srt/daemon/rotor_control/motors.py +++ b/srt/daemon/rotor_control/motors.py @@ -806,7 +806,7 @@ def __init__(self): """ super().__init__(None, None, (0.0, 360.0), (0.0, 85.0)) self.position = (60.0, 30.0) - self.client = BigDishClient("w1xm-radar-1.mitrs.org", 1234, "w1xm", "test", True) + self.client = BigDishClient("172.25.15.11", 1234, "w1xm", "test", True) def point(self, az, el): """Points the dish at a point diff --git a/srt/daemon/utilities/functions.py b/srt/daemon/utilities/functions.py index b044e4e3..1dfc5118 100644 --- a/srt/daemon/utilities/functions.py +++ b/srt/daemon/utilities/functions.py @@ -7,7 +7,7 @@ import numpy as np -def angle_within_range(actual_angle, desired_angle, bounds=0.5): +def angle_within_range(actual_angle, desired_angle, bounds=0.1): """Determines if Angles are Within a Threshold of One Another Parameters @@ -27,7 +27,7 @@ def angle_within_range(actual_angle, desired_angle, bounds=0.5): return abs(actual_angle - desired_angle) < bounds -def azel_within_range(actual_azel, desired_azel, bounds=(0.5, 0.5)): +def azel_within_range(actual_azel, desired_azel, bounds=(0.1, 0.1)): """Determines if AzEls are Within a Threshold of One Another Parameters diff --git a/srt/dashboard/app.py b/srt/dashboard/app.py index eaaa0ee6..1fff81a1 100644 --- a/srt/dashboard/app.py +++ b/srt/dashboard/app.py @@ -88,7 +88,9 @@ def generate_app(config_dir, config_dict): pio.templates.default = "seaborn" # Style Choice for Graphs curfold = Path(__file__).parent.absolute() # Generate Sidebar Objects - side_title = software + + side_title = "Medium Radio Telescope" + image_filename = curfold.joinpath( "images", "MIT_HO_logo_landscape.png" ) # replace with your own image @@ -272,7 +274,7 @@ def update_status_display(n): az_offset = el_offset = np.nan cf = np.nan bandwidth = np.nan - status_string = "SRT Not Connected" + status_string = "MRT Not Connected" vlsr = np.nan else: lat = status["location"]["latitude"] @@ -286,11 +288,11 @@ def update_status_display(n): vlsr = status["vlsr"] time_dif = time() - status["time"] if time_dif > 5: - status_string = "SRT Daemon Not Available" + status_string = "MRT Daemon Not Available" elif status["queue_size"] == 0 and status["queued_item"] == "None": - status_string = "SRT Inactive" + status_string = "MRT Inactive" else: - status_string = "SRT In Use!" + status_string = "MRT In Use!" if config_dict["SOFTWARE"] == "Very Small Radio Telescope": status_string = f""" From 2e516a9a4cb8268e608b5d38e0dfbe7d02d8fb05 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Fri, 16 Feb 2024 17:55:37 -0500 Subject: [PATCH 03/79] move block tags strobe ahead of radio wait for pps --- .../radio_process/radio_process.py | 24 ++++++++++--------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 0b670503..dc25a851 100644 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -37,7 +37,7 @@ class radio_process(gr.top_block): def __init__(self, num_bins=256, num_integrations=100000): - gr.top_block.__init__(self, "radio_process", catch_exceptions=True) + gr.top_block.__init__(self, "radio_process") #, catch_exceptions=True) ################################################## # Parameters @@ -59,7 +59,7 @@ def __init__(self, num_bins=256, num_integrations=100000): self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 self.rf_gain = rf_gain = 25 - self.rf_freq = rf_freq = freq + #self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan self.is_running = is_running = False @@ -85,6 +85,9 @@ def __init__(self, num_bins=256, num_integrations=100000): self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) self.xmlrpc_server_0_thread.daemon = True self.xmlrpc_server_0_thread.start() + self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) + self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) + self.uhd_usrp_source_1 = uhd.usrp_source( ",".join(("addr=172.25.14.11", '')), uhd.stream_args( @@ -112,8 +115,6 @@ def __init__(self, num_bins=256, num_integrations=100000): #self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) - self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) - self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) @@ -226,10 +227,11 @@ def get_freq(self): def set_freq(self, freq): self.freq = freq - self.set_rf_freq(self.freq) + #self.set_rf_freq(self.freq) self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) - + self.uhd_usrp_source_1.set_center_freq(self.freq, 0) + def get_vlsr(self): return self.vlsr @@ -285,12 +287,12 @@ def set_rf_gain(self, rf_gain): self.rf_gain = rf_gain self.uhd_usrp_source_1.set_gain(self.rf_gain, 0) - def get_rf_freq(self): - return self.rf_freq + #def get_rf_freq(self): + # return self.rf_freq - def set_rf_freq(self, rf_freq): - self.rf_freq = rf_freq - self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) + #def set_rf_freq(self, rf_freq): + # self.rf_freq = rf_freq + # self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) def get_motor_el(self): return self.motor_el From 3ae84a818f79d29c0d27df54cdee7dc1b5269646 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sun, 18 Feb 2024 00:04:31 +0000 Subject: [PATCH 04/79] modify dashboard to display raw n-point scan data and Fix axis scaling on npoint scan plot --- config/config.yaml | 2 +- srt/daemon/daemon.py | 10 +-- srt/dashboard/layouts/graphs.py | 106 +++++++++++++++++++++++++- srt/dashboard/layouts/monitor_page.py | 57 ++++++++++++-- 4 files changed, 162 insertions(+), 13 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 703b48d3..a9f5696e 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -37,7 +37,7 @@ RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 512 RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes -NUM_BEAMSWITCHES: 25 +NUM_BEAMSWITCHES: 10 BEAMWIDTH: 3.5 TSYS: 60 TCAL: 40 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 8d4ca41c..4ecdc4e6 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -167,7 +167,7 @@ def log_message(self, message): self.command_error_logs.append((time(), message)) print(message) - def n_point_scan(self, object_id): + def n_point_scan(self, object_id, grid_size=5): """Runs an N-Point (25) Scan About an Object Parameters @@ -185,17 +185,17 @@ def n_point_scan(self, object_id): cur_vlsr = self.ephemeris_vlsr[object_id] self.radio_queue.put(("vlsr", float(cur_vlsr))) self.current_vlsr = cur_vlsr - N_pnt_default = 25 + N_pnt_default = grid_size**2 rotor_loc = [] pwr_list = [] # scan_center = self.ephemeris_locations[object_id] - np_sides = [5, 5] + np_sides = [grid_size, grid_size] for scan in range(N_pnt_default): scan_center = self.ephemeris_locations[object_id] #recompute target position for every iteration self.log_message("{0} of {1} point scan.".format(scan, N_pnt_default)) - i = (scan // 5) - 2 - j = (scan % 5) - 2 + i = (scan // grid_size) - int(grid_size/2) + j = (scan % grid_size) - int(grid_size/2) el_dif = i * self.beamwidth * 0.5 az_dif_scalar = np.cos((scan_center[1] + el_dif) * np.pi / 180.0) # Avoid issues where you get close to the zenith diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index 981f549e..02846061 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -714,8 +714,110 @@ def emptygraph(xlabel, ylabel, title): return fig +def generate_npoint_raw(az_in, el_in, d_az, d_el, pow_in, cent, sides): + """Creates the n-point graph image with raw data without interpolation -def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides): + Parameters + ---------- + az_in : array_like + List of azimuth locations. + el_in : array_like + List of elevation locations. + d_az : float + Resolution of power measurements in the azimuth direction. + d_el : float + REsolution of power measurements in elevation direction. + pow_in : array_like + List of power measurements for the given locations of the antenna. + cent : array_like + Center point of the object being imaged. + sides : list + Number of pointers per side. + + Returns + ------- + fig : plotly.fig + Figure object. + """ + + # create the output grid + az_in = np.array(az_in) + el_in = np.array(el_in) + + idx_center = int(np.ceil(len(az_in)/2)) + az_center = az_in[idx_center] + el_center = el_in[idx_center] + + #az_span = (sides[0]-1)*d_az + #el_span = (sides[1]-1)*d_el + + az_range = np.linspace(az_center-d_az, az_center+d_az, sides[0]) + el_range = np.linspace(el_center-d_el, el_center+d_el, sides[1]) + + #below doesn't quite work because we are griddig a moving target + #az_range = np.linspace(az_in.min(), az_in.max(), sides[0]) + #el_range = np.linspace(el_in.min(), el_in.max(), sides[1]) + + #azout, elout = np.meshgrid(az_a, el_a) + pow_in = np.array(pow_in) + pow_grid = np.reshape(pow_in, (sides[0],sides[1])) + pmin = pow_in.min() + #p_in = pow_in - pmin + #x_l = np.linspace(-0.5, 0.5, sides[0]) + #y_l = np.linspace(-0.5, 0.5, sides[1]) + #xm, ym = np.meshgrid(x_l, y_l) + #xf = xm.flatten() + #yf = ym.flatten() + #xaout = np.linspace(-0.5, 0.5, 100) + #idxout = [(np.abs(xm - x_o)).argmin() for x_o in xaout] #get nearest neighboring point + #xo, yo = np.meshgrid(xaout, xaout) + #idxgrid, idygrid = np.meshgrid(idxout, idyout) + #idxf = idxgrid.flatten() + #idyf = idygrid.flatten() + #indices = np.transpose(np.array([idxf, idyf])) + # Interpolate the data + #interp_data_flat = pow_grid[indices] + #interp_data = np.reshape(interp_data_flat,(100,100)) + #interp_data = sinc_interp2d(xf, yf, p_in, d_az, d_el, xo, yo) + # Determine center of the object and compare to desired center. + #pow_tot = np.sum(np.sum(interp_data)) + #az_center = np.sum(np.sum(interp_data * azout)) / pow_tot + #el_center = np.sum(np.sum(interp_data * elout)) / pow_tot + #az_off = az_center - cent[0] + #el_off = el_center - cent[1] + #antext0 = "Az Center {0:.2f} deg".format(az_off) + #antext1 = "El Center {0:.2f} deg".format(el_off) + # Make the contour plot + d1 = go.Contour(z=pow_grid, x=az_range, y=el_range, colorscale="Viridis") + fig = go.Figure( + data=d1, + layout={ + "title": "Raw N-Point Scan", + "xaxis_title": "Azimuth Angle", + "yaxis_title": "Elevation Angle", + "uirevision": True, + }, + ) + #fig.add_annotation( + # x=xaout[10], + # y=xaout[20], + # xanchor="left", + # text=antext0, + # showarrow=False, + # font=dict(family="Courier New, monospace", size=13, color="#ffffff"), + #) + + #fig.add_annotation( + # x=xaout[10], + # y=xaout[10], + # text=antext1, + # xanchor="left", + # showarrow=False, + # font=dict(family="Courier New, monospace", size=13, color="#ffffff"), + #) + return fig + +def generate_npoint_interpolated(az_in, el_in, d_az, d_el, pow_in, cent, sides): """Creates the n-point graph image. Parameters @@ -773,7 +875,7 @@ def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides): fig = go.Figure( data=d1, layout={ - "title": "N-Point Scan", + "title": "N Point Sinc Interpolated", "xaxis_title": "Normalized x", "yaxis_title": "Normalized y", "uirevision": True, diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index a8ae774a..6f703e5e 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -36,7 +36,8 @@ generate_power_history_graph, generate_spectrum_graph, generate_zoom_graph, - generate_npoint, + generate_npoint_raw, + generate_npoint_interpolated, emptygraph, ) @@ -102,9 +103,13 @@ def generate_npointlayout(): [ dcc.Store(id="npoint_info", storage_type="session"), html.Div( - [dcc.Graph(id="npoint-graph")], + [dcc.Graph(id="npoint-graph-1")], className="pretty_container six columns", ), + html.Div( + [dcc.Graph(id="npoint-graph-2")], + className="pretty_container six columns", + ), # html.Div( # [dcc.Graph(id="beamsswitch-graph")], # className="pretty_container six columns", @@ -913,11 +918,52 @@ def npointstore(n, npdata): raise PreventUpdate @app.callback( - Output("npoint-graph", "figure"), + Output("npoint-graph-1", "figure"), + [Input("npoint_info", "modified_timestamp")], + [State("npoint_info", "data")], + ) + def update_n_point_raw(ts, npdata): + """Update the npoint track info + + Parameters + ---------- + ts : int + modified time stamp + npdata : dict + will hold N- point data. + + Returns + ------- + ofig : plotly.fig + Plotly figure + """ + + if ts is None: + raise PreventUpdate + if npdata is None: + return emptygraph("x", "y", "N-Point Scan") + + if npdata.get("scan_center", [1, 1])[0] == 0: + return emptygraph("x", "y", "N-Point Scan") + + az_a = [] + el_a = [] + for irot in npdata["rotor_loc"]: + az_a.append(irot[0]) + el_a.append(irot[1]) + mdiff = npdata["maxdiff"] + sc = npdata["scan_center"] + plist = npdata["pwr"] + sd = npdata["sides"] + ofig = generate_npoint_raw(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) + return ofig + + @app.callback( + Output("npoint-graph-2", "figure"), [Input("npoint_info", "modified_timestamp")], [State("npoint_info", "data")], ) - def update_n_point(ts, npdata): + def update_n_point_interpolated(ts, npdata): """Update the npoint track info Parameters @@ -950,8 +996,9 @@ def update_n_point(ts, npdata): sc = npdata["scan_center"] plist = npdata["pwr"] sd = npdata["sides"] - ofig = generate_npoint(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) + ofig = generate_npoint_interpolated(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) return ofig + @app.callback( Output("start-warning", "children"), From 172bb5cdff3e8196c36dd71287f71fb2963ee11d Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Mon, 19 Feb 2024 01:46:12 +0000 Subject: [PATCH 05/79] add control to change number of points in N-point scan function --- config/config.yaml | 2 +- srt/daemon/daemon.py | 16 ++++++- srt/dashboard/layouts/graphs.py | 34 -------------- srt/dashboard/layouts/monitor_page.py | 64 +++++++++++++++++++++++++++ 4 files changed, 79 insertions(+), 37 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index a9f5696e..057dd760 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -40,7 +40,7 @@ RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 3.5 TSYS: 60 -TCAL: 40 +TCAL: 4.5 SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 4ecdc4e6..23e2918e 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -88,6 +88,7 @@ def __init__(self, config_directory, config_dict): self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] + self.npoints = 5 #default size of grid for npoint scan # Generate Default Calibration Values # Values are Set Up so that Uncalibrated and Calibrated Spectra are the Same Values @@ -210,7 +211,7 @@ def n_point_scan(self, object_id, grid_size=5): self.rotor_destination = scan_center self.point_at_offset(*new_rotor_offsets) rotor_loc.append(self.rotor_location) - sleep(5) + sleep(3) raw_spec = get_spectrum(port=5561) p = np.sum(raw_spec) a = len(raw_spec) @@ -449,6 +450,15 @@ def stop_recording(self): if self.radio_save_task is not None: self.radio_save_task.terminate() self.radio_save_task = None + + def set_npoints(self, n): + """Set the number of points for the N point scan + + Parameters + ---------- + npoints : number of points along grid edge for npoint scan + """ + self.npoints = n def set_freq(self, frequency): """Set the Frequency of the Processing Script @@ -815,7 +825,7 @@ def srt_daemon_main(self): # If Command Starts With a Valid Object Name if command_parts[0] in self.ephemeris_locations: if command_parts[-1] == "n": # N-Point Scan About Object - self.n_point_scan(object_id=command_parts[0]) + self.n_point_scan(object_id=command_parts[0], grid_size=self.npoints) elif command_parts[-1] == "b": # Beam-Switch Away From Object self.beam_switch(object_id=command_parts[0]) else: # Point Directly At Object @@ -826,6 +836,8 @@ def srt_daemon_main(self): self.point_at_azel(*self.cal_location) elif command_name == "calibrate": self.calibrate() + elif command_name == "npointset": + self.set_npoints(n=int(command_parts[1])) elif command_name == "quit": self.quit() elif command_name == "record": diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index 02846061..38b4918c 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -748,45 +748,11 @@ def generate_npoint_raw(az_in, el_in, d_az, d_el, pow_in, cent, sides): az_center = az_in[idx_center] el_center = el_in[idx_center] - #az_span = (sides[0]-1)*d_az - #el_span = (sides[1]-1)*d_el - az_range = np.linspace(az_center-d_az, az_center+d_az, sides[0]) el_range = np.linspace(el_center-d_el, el_center+d_el, sides[1]) - - #below doesn't quite work because we are griddig a moving target - #az_range = np.linspace(az_in.min(), az_in.max(), sides[0]) - #el_range = np.linspace(el_in.min(), el_in.max(), sides[1]) - #azout, elout = np.meshgrid(az_a, el_a) pow_in = np.array(pow_in) pow_grid = np.reshape(pow_in, (sides[0],sides[1])) - pmin = pow_in.min() - #p_in = pow_in - pmin - #x_l = np.linspace(-0.5, 0.5, sides[0]) - #y_l = np.linspace(-0.5, 0.5, sides[1]) - #xm, ym = np.meshgrid(x_l, y_l) - #xf = xm.flatten() - #yf = ym.flatten() - #xaout = np.linspace(-0.5, 0.5, 100) - #idxout = [(np.abs(xm - x_o)).argmin() for x_o in xaout] #get nearest neighboring point - #xo, yo = np.meshgrid(xaout, xaout) - #idxgrid, idygrid = np.meshgrid(idxout, idyout) - #idxf = idxgrid.flatten() - #idyf = idygrid.flatten() - #indices = np.transpose(np.array([idxf, idyf])) - # Interpolate the data - #interp_data_flat = pow_grid[indices] - #interp_data = np.reshape(interp_data_flat,(100,100)) - #interp_data = sinc_interp2d(xf, yf, p_in, d_az, d_el, xo, yo) - # Determine center of the object and compare to desired center. - #pow_tot = np.sum(np.sum(interp_data)) - #az_center = np.sum(np.sum(interp_data * azout)) / pow_tot - #el_center = np.sum(np.sum(interp_data * elout)) / pow_tot - #az_off = az_center - cent[0] - #el_off = el_center - cent[1] - #antext0 = "Az Center {0:.2f} deg".format(az_off) - #antext1 = "El Center {0:.2f} deg".format(el_off) # Make the contour plot d1 = go.Contour(z=pow_grid, x=az_range, y=el_range, colorscale="Viridis") fig = go.Figure( diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 6f703e5e..ef7de4db 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -477,6 +477,41 @@ def generate_popups(software): ], id="point-modal", ), + dbc.Modal( + [ + dbc.ModalHeader("Enter the New N-point Grid Size"), + dbc.ModalBody( + [ + dcc.Input( + id="npoint-size", + type="number", + debounce=True, + placeholder="Grid Edge Points sqrt(N)", + style={"width": "100%"}, + ), + ] + ), + dbc.ModalFooter( + [ + dbc.Button( + "Yes", + id="npoint-set-btn-yes", + className="ml-auto", + # block=True, + color="primary", + ), + dbc.Button( + "No", + id="npoint-set-btn-no", + className="ml-auto", + # block=True, + color="secondary", + ), + ] + ), + ], + id="n-point-modal", + ), dbc.Modal( [ dbc.ModalHeader("Enter the New Center Frequency"), @@ -586,7 +621,9 @@ def generate_popups(software): ), ], id="offset-modal", + ), + dbc.Modal( [ dbc.ModalHeader("Start Recording"), @@ -752,6 +789,7 @@ def generate_layout(software): dbc.DropdownMenuItem("Stow", id="btn-stow"), dbc.DropdownMenuItem("Set AzEl", id="btn-point-azel"), dbc.DropdownMenuItem("Set Offsets", id="btn-set-offset"), + dbc.DropdownMenuItem("Set N-point size", id="btn-set-npoint"), ], "Radio": [ dbc.DropdownMenuItem("Set Frequency", id="btn-set-freq"), @@ -1298,6 +1336,32 @@ def point_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): if n_clicks_yes or n_clicks_no or n_clicks_btn: return not is_open return is_open + + + + @app.callback( + Output("n-point-modal", "is_open"), + [ + Input("btn-set-npoint", "n_clicks"), + Input("npoint-set-btn-yes", "n_clicks"), + Input("npoint-set-btn-no", "n_clicks"), + ], + [ + State("n-point-modal", "is_open"), + State("npoint-size", "value"), + ], + ) + def freq_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, npoints): + ctx = dash.callback_context + if not ctx.triggered: + return is_open + else: + button_id = ctx.triggered[0]["prop_id"].split(".")[0] + if button_id == "npoint-set-btn-yes": + command_thread.add_to_queue(f"npointset {npoints}") + if n_clicks_yes or n_clicks_no or n_clicks_btn: + return not is_open + return is_open @ app.callback( Output("freq-modal", "is_open"), From a6bdad7bcdb5315333b94ea537ca9faa1378675a Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 20 Feb 2024 02:17:23 +0000 Subject: [PATCH 06/79] add prototype functions for passthroughs for galactic and radec pointing with bigdish --- config/config.yaml | 4 +-- srt/daemon/daemon.py | 69 ++++++++++++++++++++++++++++++++++++++++++-- 2 files changed, 68 insertions(+), 5 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 057dd760..8a47f0b5 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -35,10 +35,10 @@ RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 512 -RADIO_INTEG_CYCLES: 10000 +RADIO_INTEG_CYCLES: 20000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 -BEAMWIDTH: 3.5 +BEAMWIDTH: 2.9 TSYS: 60 TCAL: 4.5 SAVE_DIRECTORY: /data/jlab diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 23e2918e..cbef97cd 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -211,7 +211,7 @@ def n_point_scan(self, object_id, grid_size=5): self.rotor_destination = scan_center self.point_at_offset(*new_rotor_offsets) rotor_loc.append(self.rotor_location) - sleep(3) + sleep(5) raw_spec = get_spectrum(port=5561) p = np.sum(raw_spec) a = len(raw_spec) @@ -330,8 +330,57 @@ def point_at_azel(self, az, el): while not azel_within_range(self.rotor_location, self.rotor_cmd_location): sleep(0.1) else: - self.log_message( - f"Object at {new_rotor_cmd_location} Not in Motor Bounds") + + self.log_message(f"Object at {new_rotor_cmd_location} Not in Motor Bounds") + + def point_at_galactic(self, l_pos, b_pos, duration): + """Points Antenna at a Specific Galactic longitude and lattitude + + Parameters + ---------- + l_pos : float + longitude, in degrees, to turn antenna towards + b_pos : float + lattitude, in degrees, to point antenna upwards at + duration : float + duration in seconds to continue tracking coordinate + + Returns + ------- + None + """ + + if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): + #rotor is smart enough to directly handle the command + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") + else: + #rotor needs command converted to az-el + self.log_message("direct galactic coordinate commands not yet supported for your rotor") + + def point_at_radec(self, ra_pos, dec_pos, duration): + """Points Antenna at a specific ICRS coordinate in Ra Dec + (Bigdish uses J2000) + + Parameters + ---------- + ra_pos : float + right ascension, in degrees, to turn antenna towards + dec_pos : float + declination, in degrees, to point antenna upwards at + duration : float + duration in seconds to continue tracking coordinate + + Returns + ------- + None + """ + + if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): + #rotor is smart enough to directly handle the command + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") + else: + #rotor needs command converted to az-el + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") def point_at_offset(self, az_off, el_off): """From the Current Object or Position Pointed At, Move to an Offset of That Location @@ -867,6 +916,20 @@ def srt_daemon_main(self): float(command_parts[1]), float(command_parts[2]), ) + #for bigdish enable temporary bypass of SRT command and control to directly point dish + elif command_name == "galactic": + self.point_at_galactic( + float(command_parts[1]), + float(command_parts[2]), + float(command_parts[3]), + ) + #for bigdish enable temporary bypass of SRT command and control to directly point dish + elif command_name == "radec": + self.point_at_radec( + float(command_parts[1]), + float(command_parts[2]), + float(command_parts[2]), + ) elif command_name == "offset": self.point_at_offset( float(command_parts[1]), float(command_parts[2]) From c488423c744056f5e1d907fae04c6fc269f3704c Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 20 Feb 2024 21:00:18 -0500 Subject: [PATCH 07/79] add messaging for the ettus radio to control noise calibrator functions and modify daemon to issue noise diode control commands to radio, plus various small fixes to radio flowgraph --- config/config.yaml | 5 +- config/schema.yaml | 1 + radio/radio_process/radio_process.grc | 113 +++++++++++++++++- radio/radio_save_spec/radio_save_spec.grc | 43 ++++--- srt/daemon/daemon.py | 32 +++++ .../calibrator_control_strobe.py | 64 ++++++++++ .../radio_process/radio_process.py | 112 ++++++++++------- 7 files changed, 303 insertions(+), 67 deletions(-) create mode 100644 srt/daemon/radio_control/radio_process/calibrator_control_strobe.py mode change 100644 => 100755 srt/daemon/radio_control/radio_process/radio_process.py diff --git a/config/config.yaml b/config/config.yaml index 8a47f0b5..3d6f95e7 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -35,12 +35,13 @@ RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 512 -RADIO_INTEG_CYCLES: 20000 +RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 +CAL_TYPE: NOISE_DIODE TSYS: 60 -TCAL: 4.5 +TCAL: 40 SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 diff --git a/config/schema.yaml b/config/schema.yaml index 17ebcfd2..04cec7eb 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -17,6 +17,7 @@ RADIO_INTEG_CYCLES: int() RADIO_AUTOSTART: bool() NUM_BEAMSWITCHES: int() BEAMWIDTH: num() +CAL_TYPE: enum('COLD_SKY', 'NOISE_DIODE') TSYS: num() TCAL: num() SAVE_DIRECTORY: str() diff --git a/radio/radio_process/radio_process.grc b/radio/radio_process/radio_process.grc index 355838ac..8ddb734b 100644 --- a/radio/radio_process/radio_process.grc +++ b/radio/radio_process/radio_process.grc @@ -45,6 +45,18 @@ blocks: coordinate: [108, 398] rotation: 0 state: true +- name: cal_on + id: variable + parameters: + comment: '' + value: 'False' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [176, 468.0] + rotation: 0 + state: true - name: cal_pwr id: variable parameters: @@ -69,6 +81,18 @@ blocks: coordinate: [12, 594] rotation: 0 state: true +- name: calibrator_mask + id: variable + parameters: + comment: '' + value: '0b000000000011' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [216, 380.0] + rotation: 0 + state: enabled - name: custom_window id: variable parameters: @@ -382,6 +406,7 @@ blocks: maxoutbuf: '0' minoutbuf: '0' num_ports: '1' + showports: 'False' type: complex vlen: '1' states: @@ -401,6 +426,7 @@ blocks: maxoutbuf: '0' minoutbuf: '0' num_ports: '1' + showports: 'False' type: complex vlen: '1' states: @@ -420,6 +446,7 @@ blocks: maxoutbuf: '0' minoutbuf: '0' num_ports: '1' + showports: 'False' type: complex vlen: '1' states: @@ -461,7 +488,7 @@ blocks: bus_sink: false bus_source: false bus_structure: null - coordinate: [823, 281] + coordinate: [800, 276.0] rotation: 0 state: true - name: blocks_multiply_const_vxx_0 @@ -719,7 +746,7 @@ blocks: value: 'pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, - "glon": glon, "soutrack": soutrack, "bsw": beam_switch})' + "glon": glon, "soutrack": soutrack, "bsw": beam_switch, "cal_on":cal_on})' vlen: '1' states: bus_sink: false @@ -728,6 +755,53 @@ blocks: coordinate: [548, 253] rotation: 0 state: true +- name: calibrator_control_strobe + id: epy_block + parameters: + _source_code: "\"\"\"\nblock to generate calibrator control commands for the X300\ + \ radio. \nnote that this block assumes a latency lower than the calibrator\ + \ cycle time\nand will break if that condition is not met\n\nEmbedded Python\ + \ Blocks:\n\nEach time this file is saved, GRC will instantiate the first class\ + \ it finds\nto get ports and parameters of your block. The arguments to __init__\ + \ will\nbe the parameters. All of them are required to have default values!\n\ + \"\"\"\nimport numpy as np\nfrom gnuradio import gr \nimport pmt\nimport time\n\ + import uhd\n\nclass msg_blk(gr.sync_block):\n def __init__(self, calibrator_mask=0xFFF,cal_state=False):\n\ + \ gr.sync_block.__init__(\n self,\n name=\"calibrator_msg_block\"\ + ,\n in_sig=None,\n out_sig=None\n )\n\n #input\ + \ parameters\n self.calibrator_mask = calibrator_mask\n self.cal_state\ + \ = cal_state\n\n #derived variables\n\n self.last_cal_state =\ + \ False\n \n self.message_port_register_in(pmt.intern('strobe'))\n\ + \ self.message_port_register_out(pmt.intern('command'))\n \n \ + \ self.set_msg_handler(pmt.intern('strobe'), self.handle_msg)\n\n def\ + \ handle_msg(self, msg):\n\n #send message to define next calibrator\ + \ state change\n\n if self.last_cal_state != self.cal_state:\n \ + \ if self.cal_state:\n new_cal_value = 0xFFF\n \ + \ else:\n new_cal_value = 0x000\n\n #issue command to\ + \ set toggle gpio\n\n set_gpio = pmt.make_dict()\n set_gpio =\ + \ pmt.dict_add(set_gpio, pmt.to_pmt('bank'), pmt.to_pmt('FP0A'))\n set_gpio\ + \ = pmt.dict_add(set_gpio, pmt.to_pmt('attr'), pmt.to_pmt('OUT'))\n set_gpio\ + \ = pmt.dict_add(set_gpio, pmt.to_pmt('value'), pmt.from_double(new_cal_value))\n\ + \ set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('mask'), pmt.from_double(self.calibrator_mask))\n\ + \n msg = pmt.make_dict()\n msg = pmt.dict_add(msg, pmt.to_pmt('gpio'),\ + \ set_gpio)\n\n self.message_port_pub(pmt.intern('command'), msg) #issue\ + \ message\n\n self.last_cal_state = self.cal_state\n\n " + affinity: '' + alias: '' + cal_state: cal_on + calibrator_mask: calibrator_mask + comment: '' + maxoutbuf: '0' + minoutbuf: '0' + states: + _io_cache: ('calibrator_msg_block', 'msg_blk', [('calibrator_mask', '4095'), ('cal_state', + 'False')], [('strobe', 'message', 1)], [('command', 'message', 1)], '', ['cal_state', + 'calibrator_mask']) + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [1080, 276.0] + rotation: 0 + state: true - name: dc_blocker_xx_0 id: dc_blocker_xx parameters: @@ -1184,11 +1258,34 @@ blocks: coordinate: [296, 92.0] rotation: 0 state: disabled +- name: snippet_0 + id: snippet + parameters: + alias: '' + code: 'calibrator_control_mask = self.calibrator_mask + + self.usrp0.set_gpio_attr(''FP0A'', ''CTRL'', 0x000, 0xFFF ^ calibrator_control_mask) #set + pins 2 and 3 manual + + self.usrp0.set_gpio_attr(''FP0A'', ''DDR'', 0xFFF, calibrator_control_mask) + #set pins 2 and 3 as output + + self.usrp0.set_gpio_attr(''FP0A'', ''OUT'', 0x000 , calibrator_control_mask)' + comment: '' + priority: '0' + section: main_after_init + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [200, 300.0] + rotation: 0 + state: true - name: uhd_usrp_source_1 id: uhd_usrp_source parameters: affinity: '' - alias: '' + alias: usrp0 ant0: '"RX2"' ant1: '"RX2"' ant10: '"RX2"' @@ -1640,6 +1737,7 @@ blocks: address: tcp://127.0.0.1:5558 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1661,6 +1759,7 @@ blocks: address: tcp://127.0.0.1:5559 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1682,6 +1781,7 @@ blocks: address: tcp://127.0.0.1:5563 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1703,6 +1803,7 @@ blocks: address: tcp://127.0.0.1:5562 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1724,6 +1825,7 @@ blocks: address: tcp://127.0.0.1:5560 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1745,6 +1847,7 @@ blocks: address: tcp://127.0.0.1:5561 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1770,6 +1873,7 @@ connections: - [blocks_delay_0_0, '0', blocks_stream_to_vector_0_0, '0'] - [blocks_delay_0_1, '0', blocks_stream_to_vector_0_1, '0'] - [blocks_integrate_xx_0, '0', blocks_multiply_const_xx_0, '0'] +- [blocks_message_strobe_0, strobe, calibrator_control_strobe, strobe] - [blocks_multiply_const_vxx_0, '0', blocks_add_xx_0, '0'] - [blocks_multiply_const_vxx_0_0, '0', blocks_add_xx_0, '1'] - [blocks_multiply_const_vxx_0_0_0, '0', blocks_add_xx_0, '2'] @@ -1792,6 +1896,7 @@ connections: - [blocks_stream_to_vector_0_2, '0', blocks_multiply_const_vxx_0_0_0_0, '0'] - [blocks_tags_strobe_0, '0', blocks_add_xx_0_0, '0'] - [blocks_tags_strobe_0_0, '0', blocks_add_xx_0_0, '2'] +- [calibrator_control_strobe, command, uhd_usrp_source_1, command] - [dc_blocker_xx_0, '0', blocks_skiphead_0, '0'] - [fft_vxx_0, '0', blocks_complex_to_mag_squared_0, '0'] - [osmosdr_source_0, '0', add_clock_tags, '0'] @@ -1799,4 +1904,4 @@ connections: metadata: file_format: 1 - grc_version: 3.10.5.0 + grc_version: 3.10.9.2 diff --git a/radio/radio_save_spec/radio_save_spec.grc b/radio/radio_save_spec/radio_save_spec.grc index c9273274..20d05d46 100644 --- a/radio/radio_save_spec/radio_save_spec.grc +++ b/radio/radio_save_spec/radio_save_spec.grc @@ -1,6 +1,7 @@ options: parameters: author: '' + catch_exceptions: 'True' category: '[GRC Hier Blocks]' cmake_opt: '' comment: '' @@ -125,25 +126,26 @@ blocks: \ = metadata[\"num_bins\"]\n tsys = metadata[\"tsys\"]\n tcal = metadata[\"\ tcal\"]\n cal_pwr = metadata[\"cal_pwr\"]\n vslr = metadata[\"vslr\"]\n\ \ glat = metadata[\"glat\"]\n glon = metadata[\"glon\"]\n soutrack\ - \ = metadata[\"soutrack\"]\n bsw = metadata[\"bsw\"]\n return (\n \ - \ motor_az,\n motor_el,\n freq / pow(10, 6),\n samp_rate\ - \ / pow(10, 6),\n num_integrations,\n num_bins,\n tsys,\n\ - \ tcal,\n cal_pwr,\n vslr,\n glat,\n glon,\n\ - \ soutrack,\n bsw,\n )\n\n\nclass blk(\n gr.sync_block\n\ - ): # other base classes are basic_block, decim_block, interp_block\n \"\"\ - \"Embedded Python Block example - a simple multiply const\"\"\"\n\n def __init__(\n\ - \ self, directory=\".\", filename=\"test.rad\", vec_length=4096\n \ - \ ): # only default arguments here\n \"\"\"arguments to this function\ - \ show up as parameters in GRC\"\"\"\n gr.sync_block.__init__(\n \ - \ self,\n name=\"Embedded Python Block\", # will show up\ - \ in GRC\n in_sig=[(np.float32, vec_length)],\n out_sig=None,\n\ - \ )\n # if an attribute with the same name as a parameter is found,\n\ - \ # a callback is registered (properties work, too).\n self.directory\ - \ = directory\n self.filename = filename\n self.vec_length = vec_length\n\ - \ self.obsn = 0\n\n def work(self, input_items, output_items):\n \ - \ \"\"\"example: multiply with constant\"\"\"\n file = open(pathlib.Path(self.directory,\ - \ self.filename), \"a+\")\n tags = self.get_tags_in_window(0, 0, len(input_items[0]))\n\ - \ latest_data_dict = {\n pmt.to_python(tag.key): pmt.to_python(tag.value)\ + \ = metadata[\"soutrack\"]\n bsw = metadata[\"bsw\"]\n cal_on = metadata[\"\ + cal_on\"]\n return (\n motor_az,\n motor_el,\n freq\ + \ / pow(10, 6),\n samp_rate / pow(10, 6),\n num_integrations,\n\ + \ num_bins,\n tsys,\n tcal,\n cal_pwr,\n \ + \ vslr,\n glat,\n glon,\n soutrack,\n bsw,\n \ + \ )\n\n\nclass blk(\n gr.sync_block\n): # other base classes are basic_block,\ + \ decim_block, interp_block\n \"\"\"Embedded Python Block example - a simple\ + \ multiply const\"\"\"\n\n def __init__(\n self, directory=\".\",\ + \ filename=\"test.rad\", vec_length=4096\n ): # only default arguments here\n\ + \ \"\"\"arguments to this function show up as parameters in GRC\"\"\"\ + \n gr.sync_block.__init__(\n self,\n name=\"Embedded\ + \ Python Block\", # will show up in GRC\n in_sig=[(np.float32, vec_length)],\n\ + \ out_sig=None,\n )\n # if an attribute with the same\ + \ name as a parameter is found,\n # a callback is registered (properties\ + \ work, too).\n self.directory = directory\n self.filename = filename\n\ + \ self.vec_length = vec_length\n self.obsn = 0\n\n def work(self,\ + \ input_items, output_items):\n \"\"\"example: multiply with constant\"\ + \"\"\n file = open(pathlib.Path(self.directory, self.filename), \"a+\"\ + )\n tags = self.get_tags_in_window(0, 0, len(input_items[0]))\n \ + \ latest_data_dict = {\n pmt.to_python(tag.key): pmt.to_python(tag.value)\ \ for tag in tags\n }\n yr, da, hr, mn, sc = parse_time(latest_data_dict[\"\ rx_time\"])\n (\n aznow,\n elnow,\n \ \ freq,\n bw,\n integ,\n nfreq,\n \ @@ -199,8 +201,10 @@ blocks: address: tcp://127.0.0.1:5562 affinity: '' alias: '' + bind: 'False' comment: '' hwm: '-1' + key: '' maxoutbuf: '0' minoutbuf: '0' pass_tags: 'True' @@ -220,3 +224,4 @@ connections: metadata: file_format: 1 + grc_version: 3.10.9.2 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index cbef97cd..2c8351e0 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -85,10 +85,13 @@ def __init__(self, config_directory, config_dict): self.radio_autostart = config_dict["RADIO_AUTOSTART"] self.num_beamswitches = config_dict["NUM_BEAMSWITCHES"] self.beamwidth = config_dict["BEAMWIDTH"] + self.cal_type = config_dict["CAL_TYPE"] self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] + self.npoints = 5 #default size of grid for npoint scan + self.radio_calibrator_state = False # Generate Default Calibration Values # Values are Set Up so that Uncalibrated and Calibrated Spectra are the Same Values @@ -430,6 +433,10 @@ def calibrate(self): ------- None """ + + self.set_calibrator_state(True) + sleep(0.1) + sleep( self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency ) @@ -446,6 +453,7 @@ def calibrate(self): self.cal_power = cal_data["cal_pwr"] self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) + self.set_calibrator_state(False) self.log_message("Calibration Done") def start_recording(self, name): @@ -573,6 +581,29 @@ def set_samp_rate(self, samp_rate): self.radio_save_task.terminate() self.radio_sample_frequency = samp_rate self.radio_queue.put(("samp_rate", self.radio_sample_frequency)) + + def set_calibrator_state(self, calibrator_state): + """Set the state of the calibrator via radio GPIO + + Note that this is highly system specific and must be programmed appropriately + + Parameters + ---------- + calibrator_state : boolean + whether the calibrator is on + + Returns + ------- + None + """ + if self.cal_type == "NOISE_DIODE": + #customize for appropriate control scheme + self.radio_calibrator_state = calibrator_state + self.radio_queue.put(("cal_on", self.radio_calibrator_state)) + + else: + self.log_message("Noise Source Not Implemented") + def quit(self): """Stops the Daemon Process @@ -755,6 +786,7 @@ def update_status(self): "n_point_data": self.n_point_data, "beam_switch_data": self.beam_switch_data, "time": time(), + "cal_state": self.radio_calibrator_state, } status_socket.send_json(status) sleep(0.5) diff --git a/srt/daemon/radio_control/radio_process/calibrator_control_strobe.py b/srt/daemon/radio_control/radio_process/calibrator_control_strobe.py new file mode 100644 index 00000000..cf2ba4a5 --- /dev/null +++ b/srt/daemon/radio_control/radio_process/calibrator_control_strobe.py @@ -0,0 +1,64 @@ +""" +block to generate calibrator control commands for the X300 radio. +note that this block assumes a latency lower than the calibrator cycle time +and will break if that condition is not met + +Embedded Python Blocks: + +Each time this file is saved, GRC will instantiate the first class it finds +to get ports and parameters of your block. The arguments to __init__ will +be the parameters. All of them are required to have default values! +""" +import numpy as np +from gnuradio import gr +import pmt +import time +import uhd + +class msg_blk(gr.sync_block): + def __init__(self, calibrator_mask=0xFFF,cal_state=False): + gr.sync_block.__init__( + self, + name="calibrator_msg_block", + in_sig=None, + out_sig=None + ) + + #input parameters + self.calibrator_mask = calibrator_mask + self.cal_state = cal_state + + #derived variables + + self.last_cal_state = False + #self.cal_value = 0x000 + + self.message_port_register_in(pmt.intern('strobe')) + self.message_port_register_out(pmt.intern('command')) + + self.set_msg_handler(pmt.intern('strobe'), self.handle_msg) + + def handle_msg(self, msg): + + #send message to define next calibrator state change + + if self.last_cal_state != self.cal_state: + if self.cal_state: + cal_value = 0xFFF + else: + cal_value = 0x000 + + #issue command to toggle gpio + set_gpio = pmt.make_dict() + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('bank'), pmt.to_pmt('FP0A')) + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('attr'), pmt.to_pmt('OUT')) + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('value'), pmt.from_double(cal_value)) + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('mask'), pmt.from_double(self.calibrator_mask)) + + msg = pmt.make_dict() + msg = pmt.dict_add(msg, pmt.to_pmt('gpio'), set_gpio) + self.message_port_pub(pmt.intern('command'), msg) #issue message + + self.last_cal_state = self.cal_state + + #otherwise do nothing diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py old mode 100644 new mode 100755 index dc25a851..09b025ec --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -6,7 +6,7 @@ # # GNU Radio Python Flow Graph # Title: radio_process -# GNU Radio version: 3.10.5.0 +# GNU Radio version: 3.10.9.2 from gnuradio import blocks import pmt @@ -27,17 +27,16 @@ import threading import math import numpy as np +#import radio_process_add_clock_tags as add_clock_tags # embedded python block from . import add_clock_tags -import osmosdr -import time - - +#import radio_process_calibrator_control_strobe as calibrator_control_strobe # embedded python block +from . import calibrator_control_strobe class radio_process(gr.top_block): def __init__(self, num_bins=256, num_integrations=100000): - gr.top_block.__init__(self, "radio_process") #, catch_exceptions=True) + gr.top_block.__init__(self, "radio_process", catch_exceptions=True) ################################################## # Parameters @@ -53,13 +52,13 @@ def __init__(self, num_bins=256, num_integrations=100000): self.sinc_samples = sinc_samples = np.sinc(sinc_sample_locations/np.pi) self.freq = freq = 1420000000 self.vlsr = vlsr = np.nan - self.tsys = tsys = 60 - self.tcal = tcal = 40 + self.tsys = tsys = 171 + self.tcal = tcal = 290 self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 - self.rf_gain = rf_gain = 25 - #self.rf_freq = rf_freq = freq + self.rf_gain = rf_gain = 20 + self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan self.is_running = is_running = False @@ -67,27 +66,33 @@ def __init__(self, num_bins=256, num_integrations=100000): self.glat = glat = np.nan self.fft_window = fft_window = window.blackmanharris(num_bins) self.custom_window = custom_window = sinc_samples*np.hamming(4*num_bins) + self.calibrator_mask = calibrator_mask = 0b000000000011 self.cal_values = cal_values = np.repeat(np.nan, num_bins) self.cal_pwr = cal_pwr = 1 + self.cal_on = cal_on = False self.beam_switch = beam_switch = 0 ################################################## # Blocks ################################################## - self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True) - self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True) - self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True) - self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True) - self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True) - self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True) + + self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True, True) + self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True, True) + self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True, True) + self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True, True) + self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True, True) + self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True, True) self.xmlrpc_server_0 = SimpleXMLRPCServer(('localhost', 5557), allow_none=True) self.xmlrpc_server_0.register_instance(self) self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) self.xmlrpc_server_0_thread.daemon = True self.xmlrpc_server_0_thread.start() - self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) + + #blocks_tags_strobe blocks need to come before slow radio startup commands + self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch, "cal_on": cal_on}), tag_period, pmt.intern("metadata")) self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) + self.uhd_usrp_source_1 = uhd.usrp_source( ",".join(("addr=172.25.14.11", '')), uhd.stream_args( @@ -107,14 +112,21 @@ def __init__(self, num_bins=256, num_integrations=100000): # Sleep 1 second to ensure next PPS has come time.sleep(1) - self.uhd_usrp_source_1.set_center_freq(freq, 0) + self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) self.uhd_usrp_source_1.set_antenna("RX2", 0) self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) self.uhd_usrp_source_1.set_gain(rf_gain, 0) self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) - #self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) + + ##### Manually Configure USRP GPIO + self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'CTRL', 0x000, 0xFFF ^ calibrator_mask) #set pins 2 and 3 manual + self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'DDR', 0xFFF, calibrator_mask) #set pins 2 and 3 as output + self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'OUT', 0x000 , calibrator_mask) + + self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) + self.calibrator_control_strobe = calibrator_control_strobe.msg_blk(calibrator_mask=calibrator_mask, cal_state=cal_on) self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) @@ -142,6 +154,8 @@ def __init__(self, num_bins=256, num_integrations=100000): ################################################## # Connections ################################################## + self.msg_connect((self.blocks_message_strobe_0, 'strobe'), (self.calibrator_control_strobe, 'strobe')) + self.msg_connect((self.calibrator_control_strobe, 'command'), (self.uhd_usrp_source_1, 'command')) self.connect((self.add_clock_tags, 0), (self.blocks_add_xx_0_0, 1)) self.connect((self.blocks_add_xx_0, 0), (self.fft_vxx_0, 0)) self.connect((self.blocks_add_xx_0_0, 0), (self.blocks_selector_0, 0)) @@ -196,7 +210,7 @@ def set_num_bins(self, num_bins): self.blocks_multiply_const_vxx_0_0.set_k(self.custom_window[2*self.num_bins:3*self.num_bins]) self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_num_integrations(self): @@ -206,7 +220,7 @@ def set_num_integrations(self, num_integrations): self.num_integrations = num_integrations self.set_tag_period(self.num_bins*self.num_integrations) self.blocks_multiply_const_xx_0.set_k(1.0/float(self.num_integrations)) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_sinc_sample_locations(self): return self.sinc_sample_locations @@ -227,17 +241,16 @@ def get_freq(self): def set_freq(self, freq): self.freq = freq - #self.set_rf_freq(self.freq) + self.set_rf_freq(self.freq) self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) - self.uhd_usrp_source_1.set_center_freq(self.freq, 0) - + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) + def get_vlsr(self): return self.vlsr def set_vlsr(self, vlsr): self.vlsr = vlsr - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_tsys(self): return self.tsys @@ -245,7 +258,7 @@ def get_tsys(self): def set_tsys(self, tsys): self.tsys = tsys self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_tcal(self): return self.tcal @@ -253,7 +266,7 @@ def get_tcal(self): def set_tcal(self, tcal): self.tcal = tcal self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_tag_period(self): return self.tag_period @@ -269,14 +282,14 @@ def get_soutrack(self): def set_soutrack(self, soutrack): self.soutrack = soutrack - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_samp_rate(self): return self.samp_rate def set_samp_rate(self, samp_rate): self.samp_rate = samp_rate - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) self.uhd_usrp_source_1.set_samp_rate(self.samp_rate) self.uhd_usrp_source_1.set_bandwidth(self.samp_rate, 0) @@ -287,26 +300,26 @@ def set_rf_gain(self, rf_gain): self.rf_gain = rf_gain self.uhd_usrp_source_1.set_gain(self.rf_gain, 0) - #def get_rf_freq(self): - # return self.rf_freq + def get_rf_freq(self): + return self.rf_freq - #def set_rf_freq(self, rf_freq): - # self.rf_freq = rf_freq - # self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) + def set_rf_freq(self, rf_freq): + self.rf_freq = rf_freq + self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) def get_motor_el(self): return self.motor_el def set_motor_el(self, motor_el): self.motor_el = motor_el - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_motor_az(self): return self.motor_az def set_motor_az(self, motor_az): self.motor_az = motor_az - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_is_running(self): return self.is_running @@ -320,14 +333,14 @@ def get_glon(self): def set_glon(self, glon): self.glon = glon - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_glat(self): return self.glat def set_glat(self, glat): self.glat = glat - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_fft_window(self): return self.fft_window @@ -345,6 +358,13 @@ def set_custom_window(self, custom_window): self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) + def get_calibrator_mask(self): + return self.calibrator_mask + + def set_calibrator_mask(self, calibrator_mask): + self.calibrator_mask = calibrator_mask + self.calibrator_control_strobe.calibrator_mask = self.calibrator_mask + def get_cal_values(self): return self.cal_values @@ -358,14 +378,22 @@ def get_cal_pwr(self): def set_cal_pwr(self, cal_pwr): self.cal_pwr = cal_pwr self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) + + def get_cal_on(self): + return self.cal_on + + def set_cal_on(self, cal_on): + self.cal_on = cal_on + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) + self.calibrator_control_strobe.cal_state = self.cal_on def get_beam_switch(self): return self.beam_switch def set_beam_switch(self, beam_switch): self.beam_switch = beam_switch - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def argument_parser(): @@ -383,7 +411,7 @@ def main(top_block_cls=radio_process, options=None): if options is None: options = argument_parser().parse_args() tb = top_block_cls(num_bins=options.num_bins, num_integrations=options.num_integrations) - + def sig_handler(sig=None, frame=None): tb.stop() tb.wait() From aa75cf248537b5206125a620a87c3406dd4a0cf4 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 21 Feb 2024 03:57:56 +0000 Subject: [PATCH 08/79] Erase calibration values prior to running new cal. Additionally, add a 100ms delay before accesing file with saved calibration data to make absolutely certain it's not still being written to. This appears to fix an issue whereby the calibration sometimes gets garbled and produces a scrambled output plus fix command delays during cal --- config/config.yaml | 4 ++-- srt/daemon/daemon.py | 13 +++++++++++++ 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 3d6f95e7..c28271bc 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -40,8 +40,8 @@ RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 CAL_TYPE: NOISE_DIODE -TSYS: 60 -TCAL: 40 +TSYS: 60.0 +TCAL: 48.5 SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 2c8351e0..7f0a1dd7 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -434,7 +434,16 @@ def calibrate(self): None """ + # erase existing calibration + self.cal_values = [1.0 for _ in range(self.radio_num_bins)] + self.cal_power = 1.0 + + self.radio_queue.put(("cal_pwr", self.cal_power)) + self.radio_queue.put(("cal_values", self.cal_values)) + + #turn on calibration source (if we have one) self.set_calibrator_state(True) + sleep(0.1) sleep( @@ -446,6 +455,7 @@ def calibrate(self): ) radio_cal_task.start() radio_cal_task.join(30) + sleep(0.1) path = Path(self.config_directory, "calibration.json") with open(path, "r") as input_file: cal_data = json.load(input_file) @@ -453,6 +463,8 @@ def calibrate(self): self.cal_power = cal_data["cal_pwr"] self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) + + #disable calibration source and return self.set_calibrator_state(False) self.log_message("Calibration Done") @@ -600,6 +612,7 @@ def set_calibrator_state(self, calibrator_state): #customize for appropriate control scheme self.radio_calibrator_state = calibrator_state self.radio_queue.put(("cal_on", self.radio_calibrator_state)) + sleep(0.1) else: self.log_message("Noise Source Not Implemented") From b1d8678f1695e68e9d1eb37b336eabe3129eb696 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sun, 3 Mar 2024 01:12:58 +0000 Subject: [PATCH 09/79] added explicit calon and caloff commands to daemon to allow manual trigger of noise diodes Separated calibration controls into different gui dropdown and added direct noise source command buttons --- srt/daemon/daemon.py | 4 ++++ srt/dashboard/layouts/monitor_page.py | 18 +++++++++++++++--- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 7f0a1dd7..e330bfda 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -928,6 +928,10 @@ def srt_daemon_main(self): self.stow() elif command_name == "cal": self.point_at_azel(*self.cal_location) + elif command_name == "calon": + self.set_calibrator_state(True) + elif command_name == "caloff": + self.set_calibrator_state(False) elif command_name == "calibrate": self.calibrate() elif command_name == "npointset": diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index ef7de4db..519ce438 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -795,10 +795,14 @@ def generate_layout(software): dbc.DropdownMenuItem("Set Frequency", id="btn-set-freq"), dbc.DropdownMenuItem("Set Bandwidth", id="btn-set-samp"), ], + "Calibration": [ + dbc.DropdownMenuItem("Calibrate", id="btn-calibrate"), + dbc.DropdownMenuItem("Noise Reference on", id="btn-calon"), + dbc.DropdownMenuItem("Noise Reference off", id="btn-caloff"), + ], "Routine": [ dbc.DropdownMenuItem("Start Recording", id="btn-start-record"), dbc.DropdownMenuItem("Stop Recording", id="btn-stop-record"), - dbc.DropdownMenuItem("Calibrate", id="btn-calibrate"), dbc.DropdownMenuItem("Upload CMD File", id="btn-cmd-file"), ], "Power": [ @@ -1546,18 +1550,22 @@ def run_srt_daemon(configuration_dir, configuration_dict): @ app.callback( Output("signal", "children"), [ - # Input("btn-stow", "n_clicks"), + Input("btn-stow", "n_clicks"), Input("btn-stop-record", "n_clicks"), Input("btn-quit", "n_clicks"), Input("btn-calibrate", "n_clicks"), + Input("btn-calon", "n_clicks"), + Input("btn-caloff", "n_clicks"), ], [State("recording-alert", "is_open")] ) def cmd_button_pressed( - # n_clicks_stow, + n_clicks_stow, n_clicks_stop_record, n_clicks_shutdown, n_clicks_calibrate, + n_clicks_calon, + n_clicks_caloff, is_open ): ctx = dash.callback_context @@ -1574,3 +1582,7 @@ def cmd_button_pressed( command_thread.add_to_queue("quit") elif button_id == "btn-calibrate": command_thread.add_to_queue("calibrate") + elif button_id == "btn-calon": + command_thread.add_to_queue("calon") + elif button_id == "btn-caloff": + command_thread.add_to_queue("caloff") From 5849098235a34d7d9589ab7561de04a52c9c0bcb Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sun, 3 Mar 2024 03:43:09 +0000 Subject: [PATCH 10/79] add calibrator state metadata to the .rad file output fixed .rad file export to not be broken currently does not save calibrator state but does now save file --- srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py | 1 + 1 file changed, 1 insertion(+) diff --git a/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py b/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py index 09e7c19e..b26b2f9d 100644 --- a/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py +++ b/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py @@ -154,6 +154,7 @@ def work(self, input_items, output_items): glat, glon, soutrack, + ) start_line = start_format % ( istart * bw / nfreq + efflofreq, From 5ab6b3160887487a09bbd0482c08dd644bede3a5 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 17 Sep 2024 02:37:02 +0000 Subject: [PATCH 11/79] added 10MHz and PPS lock commands at SDR startup to radio_process.py --- config/sky_coords.csv | 40 ++++++++++++++++++- .../radio_process/radio_process.py | 2 + 2 files changed, 40 insertions(+), 2 deletions(-) diff --git a/config/sky_coords.csv b/config/sky_coords.csv index 7c7a7d5e..ccad55f8 100644 --- a/config/sky_coords.csv +++ b/config/sky_coords.csv @@ -15,7 +15,7 @@ fk4,05 14 12,18 44 00,AC1 fk4,03 29 00,54 00 00,PULSAR fk4,08 30 00,-45 00 00,PS galactic,10,1,RC_CLOUD -galactic,00,0,G00 +galactic,0,0,G00 galactic,10,0,G10 galactic,20,0,G20 galactic,30,0,G30 @@ -50,4 +50,40 @@ galactic,310,0,G310 galactic,320,0,G320 galactic,330,0,G330 galactic,340,0,G340 -galactic,350,0,G350 \ No newline at end of file +galactic,350,0,G350 +galactic,5,0,G05 +galactic,15,0,G15 +galactic,25,0,G25 +galactic,35,0,G35 +galactic,45,0,G45 +galactic,55,0,G55 +galactic,65,0,G65 +galactic,75,0,G75 +galactic,85,0,G85 +galactic,95,0,G95 +galactic,105,0,G105 +galactic,115,0,G115 +galactic,125,0,G125 +galactic,135,0,G135 +galactic,145,0,G145 +galactic,155,0,G155 +galactic,165,0,G165 +galactic,175,0,G175 +galactic,185,0,G185 +galactic,195,0,G195 +galactic,205,0,G205 +galactic,215,0,G215 +galactic,225,0,G225 +galactic,235,0,G235 +galactic,245,0,G245 +galactic,255,0,G255 +galactic,265,0,G265 +galactic,275,0,G275 +galactic,285,0,G285 +galactic,295,0,G295 +galactic,305,0,G305 +galactic,315,0,G315 +galactic,325,0,G325 +galactic,335,0,G335 +galactic,345,0,G345 +galactic,355,0,G355 diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 09b025ec..a31a2443 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -103,6 +103,8 @@ def __init__(self, num_bins=256, num_integrations=100000): ) self.uhd_usrp_source_1.set_samp_rate(samp_rate) + self.uhd_usrp_source_1.set_clock_source("external") + self.uhd_usrp_source_1.set_time_source("external") _last_pps_time = self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() # Poll get_time_last_pps() every 50 ms until a change is seen while(self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() == _last_pps_time): From f56a6f727b106e1d6e959f1ba839e8881bf4dd08 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 17 Sep 2024 17:45:12 +0000 Subject: [PATCH 12/79] added offset tuning to remove DC spike and tweaked the gain a bit to try to reduce saturation by millstone Update daemon.py extend calibration delay to account for long filter settling period in radio process --- srt/daemon/daemon.py | 6 +++--- srt/daemon/radio_control/radio_process/radio_process.py | 6 ++++-- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index e330bfda..5a6d9800 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -447,7 +447,7 @@ def calibrate(self): sleep(0.1) sleep( - self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency + 4*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency ) radio_cal_task = RadioCalibrateTask( self.radio_num_bins, @@ -802,7 +802,7 @@ def update_status(self): "cal_state": self.radio_calibrator_state, } status_socket.send_json(status) - sleep(0.5) + sleep(0.1) def update_radio_settings(self): """Coordinates Sending XMLRPC Commands to the GNU Radio Script @@ -818,7 +818,7 @@ def update_radio_settings(self): method, value = self.radio_queue.get() call = getattr(rpc_server, f"set_{method}") call(value) - sleep(0.1) + sleep(0.01) def update_command_queue(self): """Waits for New Commands Coming in Over ZMQ PUSH/PULL diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index a31a2443..9dde2b20 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -57,7 +57,7 @@ def __init__(self, num_bins=256, num_integrations=100000): self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 - self.rf_gain = rf_gain = 20 + self.rf_gain = rf_gain = 10 self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan @@ -294,6 +294,7 @@ def set_samp_rate(self, samp_rate): self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) self.uhd_usrp_source_1.set_samp_rate(self.samp_rate) self.uhd_usrp_source_1.set_bandwidth(self.samp_rate, 0) + self.uhd_usrp_source_1.set_center_freq(uhd.tune_request(self.rf_freq,self.samp_rate*0.6), 0) def get_rf_gain(self): return self.rf_gain @@ -307,7 +308,8 @@ def get_rf_freq(self): def set_rf_freq(self, rf_freq): self.rf_freq = rf_freq - self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) + self.uhd_usrp_source_1.set_center_freq(uhd.tune_request(self.rf_freq,self.samp_rate*0.6), 0) + #self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) def get_motor_el(self): return self.motor_el From 922da9d4faea7b026e41484f2fcb485986e70523 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 17 Sep 2024 18:53:51 +0000 Subject: [PATCH 13/79] RF gain control added to daemon and dashboard initial RF gain added as a parameter in config --- config/config.yaml | 5 ++- config/schema.yaml | 1 + srt/daemon/daemon.py | 36 ++++++++++++++-- srt/dashboard/layouts/monitor_page.py | 60 +++++++++++++++++++++++++++ 4 files changed, 97 insertions(+), 5 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index c28271bc..5c47a3fe 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -34,8 +34,9 @@ MOTOR_BAUDRATE: 0 RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 +RADIO_RF_GAIN: 20 RADIO_NUM_BINS: 512 -RADIO_INTEG_CYCLES: 10000 +RADIO_INTEG_CYCLES: 8192 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 @@ -47,4 +48,4 @@ RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 1000 +DASHBOARD_REFRESH_MS: 200 diff --git a/config/schema.yaml b/config/schema.yaml index 04cec7eb..9379525f 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -11,6 +11,7 @@ MOTOR_BAUDRATE: int() MOTOR_PORT: str() RADIO_CF: int() RADIO_SF: int() +RADIO_RF_GAIN: int() RADIO_FREQ_CORR: int() RADIO_NUM_BINS: int() RADIO_INTEG_CYCLES: int() diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 5a6d9800..41f2e4a0 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -79,6 +79,7 @@ def __init__(self, config_directory, config_dict): self.motor_baudrate = config_dict["MOTOR_BAUDRATE"] self.radio_center_frequency = config_dict["RADIO_CF"] self.radio_sample_frequency = config_dict["RADIO_SF"] + self.radio_rf_gain = config_dict["RADIO_RF_GAIN"] self.radio_frequency_correction = config_dict["RADIO_FREQ_CORR"] self.radio_num_bins = config_dict["RADIO_NUM_BINS"] self.radio_integ_cycles = config_dict["RADIO_INTEG_CYCLES"] @@ -593,6 +594,32 @@ def set_samp_rate(self, samp_rate): self.radio_save_task.terminate() self.radio_sample_frequency = samp_rate self.radio_queue.put(("samp_rate", self.radio_sample_frequency)) + + def set_rf_gain(self, rf_gain): + """Set the rf gain of the radio + + Note that this stops any currently running raw saving tasks + + Parameters + ---------- + rf_gain : float + rf_gain for the SDR in dB + + Returns + ------- + None + """ + if self.radio_save_task is not None: + self.radio_save_task.terminate() + #save old gain and cal values + #old_gain = self.radio_rf_gain + #old_cal_values = self.cal_values + + self.radio_rf_gain = rf_gain + #self.cal_values = old_cal_values* 10**(0.1*(old_gain - self.radio_rf_gain)) + + self.radio_queue.put(("rf_gain", self.radio_rf_gain)) + #self.radio_queue.put(("cal_values", self.cal_values)) def set_calibrator_state(self, calibrator_state): """Set the state of the calibrator via radio GPIO @@ -786,6 +813,7 @@ def update_status(self): "cal_loc": self.cal_location, "horizon_points": self.horizon_points, "center_frequency": self.radio_center_frequency, + "rf_gain": self.radio_rf_gain, "frequency_correction": self.radio_frequency_correction, "bandwidth": self.radio_sample_frequency, "motor_offsets": self.rotor_offsets, @@ -862,7 +890,7 @@ def srt_daemon_main(self): self.radio_process_task.start() except RuntimeError as e: self.log_message(str(e)) - sleep(5) + sleep(5) #wait a bit for the radio to actually start up # Send Settings to the GNU Radio Script radio_params = { @@ -871,6 +899,7 @@ def srt_daemon_main(self): self.radio_center_frequency + self.radio_frequency_correction, ), "Sample Rate": ("samp_rate", self.radio_sample_frequency), + "RF Gain": ("rf_gain", self.radio_rf_gain), "Motor Azimuth": ("motor_az", self.rotor_location[0]), "Motor Elevation": ("motor_el", self.rotor_location[1]), "Motor GalLat": ( @@ -949,8 +978,9 @@ def srt_daemon_main(self): self.set_freq(frequency=float( command_parts[1]) * pow(10, 6)) elif command_name == "samp": - self.set_samp_rate(samp_rate=float( - command_parts[1]) * pow(10, 6)) + self.set_samp_rate(samp_rate=float(command_parts[1]) * pow(10, 6)) + elif command_name == "rf_gain": + self.set_rf_gain(rf_gain=float(command_parts[1])) elif command_name == "coords": self.set_coords( float(command_parts[1]), float(command_parts[2])) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 519ce438..2629e573 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -582,6 +582,41 @@ def generate_popups(software): ], id="samp-modal", ), + dbc.Modal( + [ + dbc.ModalHeader("Enter the New RF Gain"), + dbc.ModalBody( + [ + dcc.Input( + id="rf_gain", + type="number", + debounce=True, + placeholder="RF Gain (dB)", + style={"width": "100%"}, + ), + ] + ), + dbc.ModalFooter( + [ + dbc.Button( + "Yes", + id="gain-btn-yes", + className="ml-auto", + # block=True, + color="primary", + ), + dbc.Button( + "No", + id="gain-btn-no", + className="ml-auto", + # block=True, + color="secondary", + ), + ] + ), + ], + id="gain-modal", + ), dbc.Modal( [ dbc.ModalHeader("Enter the Motor Offsets"), @@ -794,6 +829,7 @@ def generate_layout(software): "Radio": [ dbc.DropdownMenuItem("Set Frequency", id="btn-set-freq"), dbc.DropdownMenuItem("Set Bandwidth", id="btn-set-samp"), + dbc.DropdownMenuItem("Set RF Gain", id="btn-set-gain"), ], "Calibration": [ dbc.DropdownMenuItem("Calibrate", id="btn-calibrate"), @@ -1415,6 +1451,30 @@ def samp_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, samp): return not is_open return is_open + @app.callback( + Output("gain-modal", "is_open"), + [ + Input("btn-set-gain", "n_clicks"), + Input("gain-btn-yes", "n_clicks"), + Input("gain-btn-no", "n_clicks"), + ], + [ + State("gain-modal", "is_open"), + State("rf_gain", "value"), + ], + ) + def gain_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, gain): + ctx = dash.callback_context + if not ctx.triggered: + return is_open + else: + button_id = ctx.triggered[0]["prop_id"].split(".")[0] + if button_id == "gain-btn-yes": + command_thread.add_to_queue(f"rf_gain {gain}") + if n_clicks_yes or n_clicks_no or n_clicks_btn: + return not is_open + return is_open + @ app.callback( Output("offset-modal", "is_open"), [ From f6d57ef9ad810043fbd2a0cdedf92f967df9ea0e Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Wed, 18 Sep 2024 17:41:39 -0400 Subject: [PATCH 14/79] heavily modified calibration command to do initial file saves for a proper calibration approach --- config/config.yaml | 1 + config/schema.yaml | 1 + srt/daemon/daemon.py | 139 +++++++++++++++++++++++++++++++++++-------- 3 files changed, 117 insertions(+), 24 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 5c47a3fe..e565b0d7 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -41,6 +41,7 @@ RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 CAL_TYPE: NOISE_DIODE +CAL_INTEGRATION_CYCLES: 5 TSYS: 60.0 TCAL: 48.5 SAVE_DIRECTORY: /data/jlab diff --git a/config/schema.yaml b/config/schema.yaml index 9379525f..1fe7be41 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -19,6 +19,7 @@ RADIO_AUTOSTART: bool() NUM_BEAMSWITCHES: int() BEAMWIDTH: num() CAL_TYPE: enum('COLD_SKY', 'NOISE_DIODE') +CAL_INTEGRATION_CYCLES: int() TSYS: num() TCAL: num() SAVE_DIRECTORY: str() diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 41f2e4a0..ab9202a7 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -11,6 +11,7 @@ from xmlrpc.client import ServerProxy from pathlib import Path from operator import add +import os import zmq import json @@ -87,6 +88,7 @@ def __init__(self, config_directory, config_dict): self.num_beamswitches = config_dict["NUM_BEAMSWITCHES"] self.beamwidth = config_dict["BEAMWIDTH"] self.cal_type = config_dict["CAL_TYPE"] + self.cal_cycles = config_dict["CAL_INTEGRATION_CYCLES"] self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] @@ -434,6 +436,11 @@ def calibrate(self): ------- None """ + + #kill any running file save operations since we're about to scramble them + + if self.radio_save_task is not None: + self.radio_save_task.terminate() # erase existing calibration self.cal_values = [1.0 for _ in range(self.radio_num_bins)] @@ -441,32 +448,116 @@ def calibrate(self): self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) - - #turn on calibration source (if we have one) - self.set_calibrator_state(True) - - sleep(0.1) - - sleep( - 4*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency - ) - radio_cal_task = RadioCalibrateTask( - self.radio_num_bins, - self.config_directory, - ) - radio_cal_task.start() - radio_cal_task.join(30) - sleep(0.1) + + ''' + simple cold sky cal for the basic SRT + ''' + + if self.cal_type == "COLD_SKY": + #define filenames for calibration measurements + cold_sky_name = "cold_sky.fits" + + #erase prior calibration files if present + cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) + if os.path.exists(cold_sky_file): + os.remove(cold_sky_file) + + #start saving new calibration file + self.radio_save_task = RadioSaveSpecFitsTask( + self.radio_sample_frequency, + self.radio_num_bins, + self.config_directory, + cold_sky_name, + ) + self.radio_save_task.start() + + sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + self.stop_recording() + + #### + + #goto calibration calculation program + + ''' + if we have a noise diode to use for calibration we need to make multiple measurements + ''' + + if self.cal_type == "NOISE_DIODE": + #define filenames for calibration measurements + cold_sky_name = "cold_sky.fits" + cal_ref_name = "cold_sky_plus_cal.fits" + + #erase prior calibration files if present + cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) + cal_ref_file=str(Path(config_directory, cal_ref_name).absolute()) + + if os.path.exists(cold_sky_file): + os.remove(cold_sky_file) + + if os.path.exists(cal_ref_file): + os.remove(cal_ref_file) + + #enable calibrator and wait for the idiotically long settling time the filters currently have + #(need to fix that eventually so integration intervals are fully independent like they should be) + + self.set_calibrator_state(True) + sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + + #save new cold sky calibration file + self.radio_save_task = RadioSaveSpecFitsTask( + self.radio_sample_frequency, + self.radio_num_bins, + self.config_directory, + cold_sky_name, + ) + self.radio_save_task.start() + + sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + self.stop_recording() + + #disable calibrator and wait for the idiotically long settling time the filters currently have + #(need to fix that eventually so integration intervals are fully independent like they should be) + + self.set_calibrator_state(False) + sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + + #save new calibration reference file + self.radio_save_task = RadioSaveSpecFitsTask( + self.radio_sample_frequency, + self.radio_num_bins, + self.config_directory, + cold_sky_name, + ) + self.radio_save_task.start() + + sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + self.stop_recording() + + + + #radio_cal_task = RadioCalibrateTask( + # self.radio_num_bins, + # self.config_directory, + # ) + # radio_cal_task.start() + # radio_cal_task.join(30) + # sleep(0.1) + + cal_data = { + "cal_values": self.cal_values, + "cal_powers": self.cal_powers + } + path = Path(self.config_directory, "calibration.json") - with open(path, "r") as input_file: - cal_data = json.load(input_file) - self.cal_values = cal_data["cal_values"] - self.cal_power = cal_data["cal_pwr"] + with open(path, "w") as input_file: + json.dump(cal_data, input_file) self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) - - #disable calibration source and return - self.set_calibrator_state(False) + + # #disable calibration source and return self.log_message("Calibration Done") def start_recording(self, name): @@ -639,7 +730,7 @@ def set_calibrator_state(self, calibrator_state): #customize for appropriate control scheme self.radio_calibrator_state = calibrator_state self.radio_queue.put(("cal_on", self.radio_calibrator_state)) - sleep(0.1) + #sleep(0.1) else: self.log_message("Noise Source Not Implemented") From 248b37a7b7a2c5004a4bf6f295ba79f9e3b03579 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 17:58:28 -0400 Subject: [PATCH 15/79] fixing thing the git rebase lost --- srt/daemon/daemon.py | 107 ++++++++---------- srt/daemon/utilities/calibration_functions.py | 72 ++++++++++++ 2 files changed, 122 insertions(+), 57 deletions(-) create mode 100644 srt/daemon/utilities/calibration_functions.py diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index ab9202a7..98cad7f8 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -27,6 +27,7 @@ ) from .utilities.object_tracker import EphemerisTracker from .utilities.functions import azel_within_range, get_spectrum +from .utilities.calibration_functions import basic_cold_sky_calibration_fit, additive_noise_calibration_fit class SmallRadioTelescopeDaemon: @@ -458,26 +459,25 @@ def calibrate(self): cold_sky_name = "cold_sky.fits" #erase prior calibration files if present - cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) + cold_sky_file=str(Path(self.config_directory, cold_sky_name).absolute()) if os.path.exists(cold_sky_file): os.remove(cold_sky_file) + self.log_message("Starting cold calibration reference measurement") + #start saving new calibration file - self.radio_save_task = RadioSaveSpecFitsTask( - self.radio_sample_frequency, - self.radio_num_bins, - self.config_directory, - cold_sky_name, - ) - self.radio_save_task.start() + sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + self.start_recording(name=cold_sky_name, file_dir=self.config_dir) + sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) + self.stop_recording() - sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + ### compute calibration corrections + + cal_values, cal_power = basic_cold_sky_calibration_fit(cold_sky_file, self.temp_sys, self.temp_cal, 20) - self.stop_recording() - #### - #goto calibration calculation program ''' if we have a noise diode to use for calibration we need to make multiple measurements @@ -489,8 +489,8 @@ def calibrate(self): cal_ref_name = "cold_sky_plus_cal.fits" #erase prior calibration files if present - cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) - cal_ref_file=str(Path(config_directory, cal_ref_name).absolute()) + cold_sky_file=str(Path(self.config_directory, cold_sky_name).absolute()) + cal_ref_file=str(Path(self.config_directory, cal_ref_name).absolute()) if os.path.exists(cold_sky_file): os.remove(cold_sky_file) @@ -501,66 +501,60 @@ def calibrate(self): #enable calibrator and wait for the idiotically long settling time the filters currently have #(need to fix that eventually so integration intervals are fully independent like they should be) + self.log_message("Starting hot calibration reference measurement") + self.set_calibrator_state(True) sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) - - #save new cold sky calibration file - self.radio_save_task = RadioSaveSpecFitsTask( - self.radio_sample_frequency, - self.radio_num_bins, - self.config_directory, - cold_sky_name, - ) - self.radio_save_task.start() - - sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) - + self.start_recording(name=cal_ref_name, file_dir=self.config_directory) + sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) self.stop_recording() #disable calibrator and wait for the idiotically long settling time the filters currently have #(need to fix that eventually so integration intervals are fully independent like they should be) + self.log_message("Starting cold calibration reference measurement") + self.set_calibrator_state(False) sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + self.start_recording(name=cold_sky_name, file_dir=self.config_directory) + sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) + self.stop_recording() - #save new calibration reference file - self.radio_save_task = RadioSaveSpecFitsTask( - self.radio_sample_frequency, - self.radio_num_bins, - self.config_directory, - cold_sky_name, - ) - self.radio_save_task.start() - - sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + cal_values, cal_power = additive_noise_calibration_fit(cold_sky_file, cal_ref_file, self.temp_sys, self.temp_cal, 20) - self.stop_recording() + #erase old cal file to prevent wierdness + calibration_path = Path(self.config_directory, "calibration.json") + if os.path.exists(calibration_path): + os.remove(calibration_path) - #radio_cal_task = RadioCalibrateTask( - # self.radio_num_bins, - # self.config_directory, - # ) - # radio_cal_task.start() - # radio_cal_task.join(30) - # sleep(0.1) + #save result - cal_data = { - "cal_values": self.cal_values, - "cal_powers": self.cal_powers + file_output = { + "cal_pwr": cal_power, + "cal_values": cal_values.tolist(), } + with open(calibration_path, "w") as outfile: + json.dump(file_output, outfile) + #write corrections back to processing + + #readback from file is to circumvent a wierd formatting issue I can't figure out + + sleep(0.1) path = Path(self.config_directory, "calibration.json") - with open(path, "w") as input_file: - json.dump(cal_data, input_file) + with open(path, "r") as input_file: + cal_data = json.load(input_file) + self.cal_values = cal_data["cal_values"] + self.cal_power = cal_data["cal_pwr"] self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) - # #disable calibration source and return + self.log_message("Calibration Done") - def start_recording(self, name): + def start_recording(self, name, file_dir): """Starts Recording Data Parameters @@ -575,14 +569,14 @@ def start_recording(self, name): if self.radio_save_task is None: if name is None: self.radio_save_task = RadioSaveRawTask( - self.radio_sample_frequency, self.save_dir, name + self.radio_sample_frequency, file_dir, name ) elif name.endswith(".rad"): name = None if name == "*.rad" else name self.radio_save_task = RadioSaveSpecRadTask( self.radio_sample_frequency, self.radio_num_bins, - self.save_dir, + file_dir, name, ) elif name.endswith(".fits"): @@ -590,12 +584,12 @@ def start_recording(self, name): self.radio_save_task = RadioSaveSpecFitsTask( self.radio_sample_frequency, self.radio_num_bins, - self.save_dir, + file_dir, name, ) else: self.radio_save_task = RadioSaveRawTask( - self.radio_sample_frequency, self.save_dir, name + self.radio_sample_frequency, file_dir, name ) self.radio_save_task.start() else: @@ -1060,8 +1054,7 @@ def srt_daemon_main(self): self.quit() elif command_name == "record": self.start_recording( - name=(None if len(command_parts) - <= 1 else command_parts[1]) + name=(None if len(command_parts) <= 1 else command_parts[1]), file_dir=self.save_dir ) elif command_name == "roff": self.stop_recording() diff --git a/srt/daemon/utilities/calibration_functions.py b/srt/daemon/utilities/calibration_functions.py new file mode 100644 index 00000000..97256ad7 --- /dev/null +++ b/srt/daemon/utilities/calibration_functions.py @@ -0,0 +1,72 @@ +"""calibration_functions.py + +dsheen 2024/09/18 +Calibration Mathhematics for new SRT calibration scheme + +reimplements basic cold sky cal implemented directly in gnuradio +and adds additional capabilities for more advanced telescopes. +""" + +import numpy as np +import numpy.polynomial.polynomial as poly +from astropy.io import fits + +def get_averaged_spectrum(fits_file): + """ + open fits file and average all included spectra together + """ + spectrum_file = fits.open(fits_file) + average_spectrum = np.zeros(len(spectrum_file[0].data),dtype=np.float64) + + num_spectra = len(spectrum_file) + for i in range(0,num_spectra): + spectrum=spectrum_file[i] + average_spectrum += spectrum.data + + average_spectrum /= num_spectra + + return average_spectrum + + +def basic_cold_sky_calibration_fit(cold_sky_reference_filepath, t_sys=300, t_cal=300, polynomial_order=20): + """ + very basic calibration for single point temperature reference measurement. + calculates a polynomial fit for the spectrum and appropriately normalizes it + """ + + average_cold_sky_spectrum = get_averaged_spectrum(cold_sky_reference_filepath) + relative_freq_values = np.linspace(-1, 1, len(average_cold_sky_spectrum)) + polynomial_fit = poly.Polynomial.fit(relative_freq_values, average_cold_sky_spectrum, polynomial_order,) + + smoothed_cold_sky_spectrum = polynomial_fit(relative_freq_values) + average_value = np.average(smoothed_cold_sky_spectrum) + normalized_gain_spectrum = smoothed_cold_sky_spectrum/average_value + average_gain_correction = average_value/(t_sys+t_cal) + + + return normalized_gain_spectrum, average_gain_correction + + +def additive_noise_calibration_fit(cold_sky_reference_filepath, calibrator_reference_filepath, t_sys=300, t_cal=300, polynomial_order=20): + + average_cold_sky_spectrum = get_averaged_spectrum(cold_sky_reference_filepath) + average_calibrator_plus_sky_spectrum = get_averaged_spectrum(calibrator_reference_filepath) + average_calibrator_spectrum = average_calibrator_plus_sky_spectrum - average_cold_sky_spectrum + + relative_freq_values = np.linspace(-1, 1, len(average_cold_sky_spectrum)) + polynomial_fit = poly.Polynomial.fit(relative_freq_values, average_calibrator_spectrum, polynomial_order,) + + smoothed_calibrator_spectrum = polynomial_fit(relative_freq_values) + average_value = np.average(smoothed_calibrator_spectrum) + normalized_gain_spectrum = smoothed_calibrator_spectrum/average_value + average_gain_correction = average_value/t_cal + + return normalized_gain_spectrum, average_gain_correction + + + + + + + + From fcd7bbd6a4c58c5c3b78ee9df33e93b122dd67b3 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 17:59:37 -0400 Subject: [PATCH 16/79] . --- config/sky_coords.csv | 40 ++-------------------------------------- 1 file changed, 2 insertions(+), 38 deletions(-) diff --git a/config/sky_coords.csv b/config/sky_coords.csv index ccad55f8..7c7a7d5e 100644 --- a/config/sky_coords.csv +++ b/config/sky_coords.csv @@ -15,7 +15,7 @@ fk4,05 14 12,18 44 00,AC1 fk4,03 29 00,54 00 00,PULSAR fk4,08 30 00,-45 00 00,PS galactic,10,1,RC_CLOUD -galactic,0,0,G00 +galactic,00,0,G00 galactic,10,0,G10 galactic,20,0,G20 galactic,30,0,G30 @@ -50,40 +50,4 @@ galactic,310,0,G310 galactic,320,0,G320 galactic,330,0,G330 galactic,340,0,G340 -galactic,350,0,G350 -galactic,5,0,G05 -galactic,15,0,G15 -galactic,25,0,G25 -galactic,35,0,G35 -galactic,45,0,G45 -galactic,55,0,G55 -galactic,65,0,G65 -galactic,75,0,G75 -galactic,85,0,G85 -galactic,95,0,G95 -galactic,105,0,G105 -galactic,115,0,G115 -galactic,125,0,G125 -galactic,135,0,G135 -galactic,145,0,G145 -galactic,155,0,G155 -galactic,165,0,G165 -galactic,175,0,G175 -galactic,185,0,G185 -galactic,195,0,G195 -galactic,205,0,G205 -galactic,215,0,G215 -galactic,225,0,G225 -galactic,235,0,G235 -galactic,245,0,G245 -galactic,255,0,G255 -galactic,265,0,G265 -galactic,275,0,G275 -galactic,285,0,G285 -galactic,295,0,G295 -galactic,305,0,G305 -galactic,315,0,G315 -galactic,325,0,G325 -galactic,335,0,G335 -galactic,345,0,G345 -galactic,355,0,G355 +galactic,350,0,G350 \ No newline at end of file From 7f1a594832b8f4701bbd2516394db6385d72d079 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sat, 21 Sep 2024 22:32:25 +0000 Subject: [PATCH 17/79] added catch for exception in monitor.py objects import since that seems broken --- srt/daemon/daemon.py | 4 ++-- srt/dashboard/layouts/monitor_page.py | 19 ++++++++++++------- 2 files changed, 14 insertions(+), 9 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 98cad7f8..e810c90e 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -833,7 +833,7 @@ def update_rotor_status(self): ) and (time() - start_time) < 10: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() - print(past_rotor_location, self.rotor_location) + #print(past_rotor_location, self.rotor_location) if not self.rotor_location == past_rotor_location: g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord( self.rotor_location @@ -850,7 +850,7 @@ def update_rotor_status(self): else: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() - print(self.rotor_location) + #print(self.rotor_location) if not self.rotor_location == past_rotor_location: g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord( self.rotor_location diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 2629e573..9a354bcf 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -45,15 +45,20 @@ from srt import config_loader -root_folder = Path(__file__).parent.parent.parent.parent +#root_folder = Path(__file__).parent.parent.parent.parent +#the above appears to be broken +root_folder = "$HOME/srt-py" - -def get_all_objects(config_file="config/sky_coords.csv",): - table = Table.read(Path(root_folder, config_file), format="ascii.csv") +def get_all_objects(coords_file="config/sky_coords.csv",): all_objects = ["Sun", "Moon"] - for index, row in enumerate(table): - name = row["name"] - all_objects.append(name) + try: + table = Table.read(Path(root_folder, coords_file), format="ascii.csv") + + for index, row in enumerate(table): + name = row["name"] + all_objects.append(name) + except: + table = all_objects #just to do something return all_objects From f67aeee8228ff5e1e16c7e2692838404c5ef02d4 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 18:50:32 -0400 Subject: [PATCH 18/79] minor tweak to monitor page but seems like something is very borked and idk quite what --- srt/dashboard/layouts/monitor_page.py | 38 +++++++++++++-------------- 1 file changed, 18 insertions(+), 20 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 9a354bcf..f7b2e13a 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1532,24 +1532,24 @@ def record_click_func( return not is_open return is_open - @ app.callback( - Output("recording-alert", "is_open"), - [Input("record-btn-yes", "n_clicks"), - Input("btn-stop-record", "n_clicks")], - [], - ) - def record_alert_func(n_clicks_start, n_clicks_stop): - ctx = dash.callback_context - if not ctx.triggered: - return False - else: - if not n_clicks_start: - return False - if not n_clicks_stop: - return True - if n_clicks_start == n_clicks_stop: - return False - return True + #@ app.callback( + # Output("recording-alert", "is_open"), + # [Input("record-btn-yes", "n_clicks"), + # Input("btn-stop-record", "n_clicks")], + # [], + #) + #def record_alert_func(n_clicks_start, n_clicks_stop): + # ctx = dash.callback_context + # if not ctx.triggered: + # return False + # else: + # if not n_clicks_start: + # return False + # if not n_clicks_stop: + # return True + # if n_clicks_start == n_clicks_stop: + # return False + # return True @ app.callback( Output("cmd-file-modal", "is_open"), @@ -1631,7 +1631,6 @@ def cmd_button_pressed( n_clicks_calibrate, n_clicks_calon, n_clicks_caloff, - is_open ): ctx = dash.callback_context if not ctx.triggered: @@ -1642,7 +1641,6 @@ def cmd_button_pressed( command_thread.add_to_queue("stow") if button_id == "btn-stop-record": command_thread.add_to_queue("roff") - return not is_open elif button_id == "btn-quit": command_thread.add_to_queue("quit") elif button_id == "btn-calibrate": From 579d2a552745f560d2e5ae331192d661d45f5a85 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 19:07:35 -0400 Subject: [PATCH 19/79] mod command_button_presed definition in monitor.py to hopefully work again --- srt/dashboard/layouts/monitor_page.py | 1 - 1 file changed, 1 deletion(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index f7b2e13a..220f147e 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1622,7 +1622,6 @@ def run_srt_daemon(configuration_dir, configuration_dict): Input("btn-calon", "n_clicks"), Input("btn-caloff", "n_clicks"), ], - [State("recording-alert", "is_open")] ) def cmd_button_pressed( n_clicks_stow, From 81b39f65715df687a54fa55dc878e9268c330f3a Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sat, 21 Sep 2024 23:28:14 +0000 Subject: [PATCH 20/79] FINALLY! actually have everything working --- config/config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/config.yaml b/config/config.yaml index e565b0d7..a4ddb392 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -49,4 +49,4 @@ RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 200 +DASHBOARD_REFRESH_MS: 500 From 5e7b373e8a44c7ba0f94ea4c0fa6c9843ac8a82b Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 19:34:36 -0400 Subject: [PATCH 21/79] Removed old bad interpolated N point graph and changed graphs order --- srt/dashboard/layouts/monitor_page.py | 149 +++++++++++++------------- 1 file changed, 75 insertions(+), 74 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 220f147e..d3d0280c 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -37,7 +37,6 @@ generate_spectrum_graph, generate_zoom_graph, generate_npoint_raw, - generate_npoint_interpolated, emptygraph, ) @@ -95,6 +94,33 @@ def generate_first_row(): ) + + +def generate_second_row(): + """Generates Second Row (AzEl and AzEl Zoom) Display + + Returns + ------- + Div Containing Second Row Objects + """ + return html.Div( + html.Div( + [ + html.Div( + [dcc.Graph(id="az-el-graph")], + className="pretty_container six columns", + ), + + html.Div( + [dcc.Graph(id="zoom-graph")], + className="pretty_container six columns", + ), + ], + className="flex-display", + style={"margin": dict(l=10, r=5, t=5, b=5)}, + ), + ) + def generate_npointlayout(): """Generates N Point Display @@ -111,10 +137,10 @@ def generate_npointlayout(): [dcc.Graph(id="npoint-graph-1")], className="pretty_container six columns", ), - html.Div( - [dcc.Graph(id="npoint-graph-2")], - className="pretty_container six columns", - ), + #html.Div( + # [dcc.Graph(id="npoint-graph-2")], + # className="pretty_container six columns", + # ), # html.Div( # [dcc.Graph(id="beamsswitch-graph")], # className="pretty_container six columns", @@ -130,31 +156,6 @@ def generate_npointlayout(): ) -def generate_second_row(): - """Generates Second Row (AzEl and AzEl Zoom) Display - - Returns - ------- - Div Containing Second Row Objects - """ - return html.Div( - html.Div( - [ - html.Div( - [dcc.Graph(id="az-el-graph")], - className="pretty_container six columns", - ), - - html.Div( - [dcc.Graph(id="zoom-graph")], - className="pretty_container six columns", - ), - ], - className="flex-display", - style={"margin": dict(l=10, r=5, t=5, b=5)}, - ), - ) - def generate_third_row(): """Generates Third Row (AzEl Time) Display @@ -855,8 +856,8 @@ def generate_layout(software): layout = html.Div( [ generate_navbar(drop_down_buttons_vsrt), - dbc.Alert("Recording", color="danger", - id="recording-alert", is_open=False), + #dbc.Alert("Recording", color="danger", + # id="recording-alert", is_open=False), generate_first_row(), generate_second_row(), generate_third_row(), @@ -868,8 +869,8 @@ def generate_layout(software): layout = html.Div( [ generate_navbar(drop_down_buttons_srt), - dbc.Alert("Recording", color="danger", - id="recording-alert", is_open=False), + #dbc.Alert("Recording", color="danger", + # id="recording-alert", is_open=False), generate_first_row(), generate_npointlayout(), generate_second_row(), @@ -1041,46 +1042,46 @@ def update_n_point_raw(ts, npdata): ofig = generate_npoint_raw(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) return ofig - @app.callback( - Output("npoint-graph-2", "figure"), - [Input("npoint_info", "modified_timestamp")], - [State("npoint_info", "data")], - ) - def update_n_point_interpolated(ts, npdata): - """Update the npoint track info - - Parameters - ---------- - ts : int - modified time stamp - npdata : dict - will hold N- point data. - - Returns - ------- - ofig : plotly.fig - Plotly figure - """ - - if ts is None: - raise PreventUpdate - if npdata is None: - return emptygraph("x", "y", "N-Point Scan") - - if npdata.get("scan_center", [1, 1])[0] == 0: - return emptygraph("x", "y", "N-Point Scan") - - az_a = [] - el_a = [] - for irot in npdata["rotor_loc"]: - az_a.append(irot[0]) - el_a.append(irot[1]) - mdiff = npdata["maxdiff"] - sc = npdata["scan_center"] - plist = npdata["pwr"] - sd = npdata["sides"] - ofig = generate_npoint_interpolated(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) - return ofig + # @app.callback( + # Output("npoint-graph-2", "figure"), + # [Input("npoint_info", "modified_timestamp")], + # [State("npoint_info", "data")], + # ) + # def update_n_point_interpolated(ts, npdata): + # """Update the npoint track info + + # Parameters + # ---------- + # ts : int + # modified time stamp + # npdata : dict + # will hold N- point data. + + # Returns + # ------- + # ofig : plotly.fig + # Plotly figure + # """ + + # if ts is None: + # raise PreventUpdate + # if npdata is None: + # return emptygraph("x", "y", "N-Point Scan") + + # if npdata.get("scan_center", [1, 1])[0] == 0: + # return emptygraph("x", "y", "N-Point Scan") + + # az_a = [] + # el_a = [] + # for irot in npdata["rotor_loc"]: + # az_a.append(irot[0]) + # el_a.append(irot[1]) + # mdiff = npdata["maxdiff"] + # sc = npdata["scan_center"] + # plist = npdata["pwr"] + # sd = npdata["sides"] + # ofig = generate_npoint_interpolated(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) + # return ofig @app.callback( From 0c008c5f75ed2cd39e3534e9480e70fecca78b87 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 19:45:38 -0400 Subject: [PATCH 22/79] swapped N point order in display --- srt/dashboard/layouts/monitor_page.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index d3d0280c..950d93d2 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -872,8 +872,8 @@ def generate_layout(software): #dbc.Alert("Recording", color="danger", # id="recording-alert", is_open=False), generate_first_row(), - generate_npointlayout(), generate_second_row(), + generate_npointlayout(), generate_third_row(), generate_popups(software), html.Div(id="signal", style={"display": "none"}), From 65baad9c18e244f0049248a4960b38002cd0189a Mon Sep 17 00:00:00 2001 From: Oliver Lok Trevor Date: Fri, 9 Feb 2024 22:08:00 -0500 Subject: [PATCH 23/79] Big Dish control is working! Updated with MIT location. --- config/config.yaml | 48 +- config/schema.yaml | 2 +- radio/radio_process/radio_process.grc | 469 ++++++++++- radio/radio_process/radioonly.grc | 465 ++++++++++- .../radio_process/radio_process.py | 727 ++++-------------- srt/daemon/rotor_control/bigdish_client.py | 58 ++ srt/daemon/rotor_control/motors.py | 43 ++ srt/daemon/rotor_control/rotors.py | 5 +- 8 files changed, 1223 insertions(+), 594 deletions(-) create mode 100755 srt/daemon/rotor_control/bigdish_client.py diff --git a/config/config.yaml b/config/config.yaml index edf7a303..cf7f9dc5 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -1,49 +1,49 @@ SOFTWARE: Small Radio Telescope STATION: - latitude: 42.5 - longitude: -71.5 - name: Haystack + latitude: 42.360236 + longitude: -71.089694 + name: W1XM EMERGENCY_CONTACT: - name: John Doe - email: test@example.com - phone_number: 555-555-5555 + name: Oliver Trevor + email: olt@mit.edu + phone_number: 925-367-3607 AZLIMITS: - lower_bound: 38.0 - upper_bound: 355.0 + lower_bound: 0.0 + upper_bound: 360.0 ELLIMITS: lower_bound: 0.0 - upper_bound: 89.0 + upper_bound: 85.0 STOW_LOCATION: - azimuth: 38.0 - elevation: 0.0 + azimuth: 60.0 + elevation: 30.0 CAL_LOCATION: - azimuth: 120.0 - elevation: 7.0 + azimuth: 270.0 + elevation: 50.0 HORIZON_POINTS: - azimuth: 0 elevation: 0 - azimuth: 120 - elevation: 5 + elevation: 0 - azimuth: 240 - elevation: 5 + elevation: 0 - azimuth: 360 elevation: 0 -MOTOR_TYPE: NONE -MOTOR_PORT: /dev/ttyUSB0 -MOTOR_BAUDRATE: 600 +MOTOR_TYPE: W1XMBIGDISH +MOTOR_PORT: None +MOTOR_BAUDRATE: 0 RADIO_CF: 1420000000 -RADIO_SF: 2400000 -RADIO_FREQ_CORR: -50000 +RADIO_SF: 2000000 +RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 256 -RADIO_INTEG_CYCLES: 100000 +RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 25 BEAMWIDTH: 7.0 -TSYS: 171 -TCAL: 290 +TSYS: 60 +TCAL: 40 SAVE_DIRECTORY: ~/Desktop/SRT-Saves RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 3000 +DASHBOARD_REFRESH_MS: 1000 diff --git a/config/schema.yaml b/config/schema.yaml index 779ad0d9..17ebcfd2 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -6,7 +6,7 @@ ELLIMITS: include('limit') STOW_LOCATION: include('az_el_point') CAL_LOCATION: include('az_el_point') HORIZON_POINTS: list(include('az_el_point'), min=0) -MOTOR_TYPE: enum('ALFASPID', 'H180MOUNT', 'PUSHROD', 'NONE') +MOTOR_TYPE: enum('ALFASPID', 'H180MOUNT', 'PUSHROD', 'NONE', 'W1XMBIGDISH') MOTOR_BAUDRATE: int() MOTOR_PORT: str() RADIO_CF: int() diff --git a/radio/radio_process/radio_process.grc b/radio/radio_process/radio_process.grc index 8ae67250..355838ac 100644 --- a/radio/radio_process/radio_process.grc +++ b/radio/radio_process/radio_process.grc @@ -165,11 +165,35 @@ blocks: coordinate: [100, 268] rotation: 0 state: true +- name: rf_freq + id: variable + parameters: + comment: '' + value: freq + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [984, 12.0] + rotation: 0 + state: enabled +- name: rf_gain + id: variable + parameters: + comment: '' + value: '20' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [896, 12.0] + rotation: 0 + state: enabled - name: samp_rate id: variable parameters: comment: '' - value: '2400000' + value: '2000000' states: bus_sink: false bus_source: false @@ -1157,7 +1181,443 @@ blocks: bus_sink: false bus_source: false bus_structure: null - coordinate: [293, 99] + coordinate: [296, 92.0] + rotation: 0 + state: disabled +- name: uhd_usrp_source_1 + id: uhd_usrp_source + parameters: + affinity: '' + alias: '' + ant0: '"RX2"' + ant1: '"RX2"' + ant10: '"RX2"' + ant11: '"RX2"' + ant12: '"RX2"' + ant13: '"RX2"' + ant14: '"RX2"' + ant15: '"RX2"' + ant16: '"RX2"' + ant17: '"RX2"' + ant18: '"RX2"' + ant19: '"RX2"' + ant2: '"RX2"' + ant20: '"RX2"' + ant21: '"RX2"' + ant22: '"RX2"' + ant23: '"RX2"' + ant24: '"RX2"' + ant25: '"RX2"' + ant26: '"RX2"' + ant27: '"RX2"' + ant28: '"RX2"' + ant29: '"RX2"' + ant3: '"RX2"' + ant30: '"RX2"' + ant31: '"RX2"' + ant4: '"RX2"' + ant5: '"RX2"' + ant6: '"RX2"' + ant7: '"RX2"' + ant8: '"RX2"' + ant9: '"RX2"' + bw0: samp_rate + bw1: '0' + bw10: '0' + bw11: '0' + bw12: '0' + bw13: '0' + bw14: '0' + bw15: '0' + bw16: '0' + bw17: '0' + bw18: '0' + bw19: '0' + bw2: '0' + bw20: '0' + bw21: '0' + bw22: '0' + bw23: '0' + bw24: '0' + bw25: '0' + bw26: '0' + bw27: '0' + bw28: '0' + bw29: '0' + bw3: '0' + bw30: '0' + bw31: '0' + bw4: '0' + bw5: '0' + bw6: '0' + bw7: '0' + bw8: '0' + bw9: '0' + center_freq0: rf_freq + center_freq1: '0' + center_freq10: '0' + center_freq11: '0' + center_freq12: '0' + center_freq13: '0' + center_freq14: '0' + center_freq15: '0' + center_freq16: '0' + center_freq17: '0' + center_freq18: '0' + center_freq19: '0' + center_freq2: '0' + center_freq20: '0' + center_freq21: '0' + center_freq22: '0' + center_freq23: '0' + center_freq24: '0' + center_freq25: '0' + center_freq26: '0' + center_freq27: '0' + center_freq28: '0' + center_freq29: '0' + center_freq3: '0' + center_freq30: '0' + center_freq31: '0' + center_freq4: '0' + center_freq5: '0' + center_freq6: '0' + center_freq7: '0' + center_freq8: '0' + center_freq9: '0' + clock_rate: 0e0 + clock_source0: '' + clock_source1: '' + clock_source2: '' + clock_source3: '' + clock_source4: '' + clock_source5: '' + clock_source6: '' + clock_source7: '' + comment: '' + dc_offs0: 0+0j + dc_offs1: 0+0j + dc_offs10: 0+0j + dc_offs11: 0+0j + dc_offs12: 0+0j + dc_offs13: 0+0j + dc_offs14: 0+0j + dc_offs15: 0+0j + dc_offs16: 0+0j + dc_offs17: 0+0j + dc_offs18: 0+0j + dc_offs19: 0+0j + dc_offs2: 0+0j + dc_offs20: 0+0j + dc_offs21: 0+0j + dc_offs22: 0+0j + dc_offs23: 0+0j + dc_offs24: 0+0j + dc_offs25: 0+0j + dc_offs26: 0+0j + dc_offs27: 0+0j + dc_offs28: 0+0j + dc_offs29: 0+0j + dc_offs3: 0+0j + dc_offs30: 0+0j + dc_offs31: 0+0j + dc_offs4: 0+0j + dc_offs5: 0+0j + dc_offs6: 0+0j + dc_offs7: 0+0j + dc_offs8: 0+0j + dc_offs9: 0+0j + dc_offs_enb0: auto + dc_offs_enb1: default + dc_offs_enb10: default + dc_offs_enb11: default + dc_offs_enb12: default + dc_offs_enb13: default + dc_offs_enb14: default + dc_offs_enb15: default + dc_offs_enb16: default + dc_offs_enb17: default + dc_offs_enb18: default + dc_offs_enb19: default + dc_offs_enb2: default + dc_offs_enb20: default + dc_offs_enb21: default + dc_offs_enb22: default + dc_offs_enb23: default + dc_offs_enb24: default + dc_offs_enb25: default + dc_offs_enb26: default + dc_offs_enb27: default + dc_offs_enb28: default + dc_offs_enb29: default + dc_offs_enb3: default + dc_offs_enb30: default + dc_offs_enb31: default + dc_offs_enb4: default + dc_offs_enb5: default + dc_offs_enb6: default + dc_offs_enb7: default + dc_offs_enb8: default + dc_offs_enb9: default + dev_addr: '"addr=172.25.14.11"' + dev_args: '' + gain0: rf_gain + gain1: '0' + gain10: '0' + gain11: '0' + gain12: '0' + gain13: '0' + gain14: '0' + gain15: '0' + gain16: '0' + gain17: '0' + gain18: '0' + gain19: '0' + gain2: '0' + gain20: '0' + gain21: '0' + gain22: '0' + gain23: '0' + gain24: '0' + gain25: '0' + gain26: '0' + gain27: '0' + gain28: '0' + gain29: '0' + gain3: '0' + gain30: '0' + gain31: '0' + gain4: '0' + gain5: '0' + gain6: '0' + gain7: '0' + gain8: '0' + gain9: '0' + gain_type0: default + gain_type1: default + gain_type10: default + gain_type11: default + gain_type12: default + gain_type13: default + gain_type14: default + gain_type15: default + gain_type16: default + gain_type17: default + gain_type18: default + gain_type19: default + gain_type2: default + gain_type20: default + gain_type21: default + gain_type22: default + gain_type23: default + gain_type24: default + gain_type25: default + gain_type26: default + gain_type27: default + gain_type28: default + gain_type29: default + gain_type3: default + gain_type30: default + gain_type31: default + gain_type4: default + gain_type5: default + gain_type6: default + gain_type7: default + gain_type8: default + gain_type9: default + iq_imbal0: 0+0j + iq_imbal1: 0+0j + iq_imbal10: 0+0j + iq_imbal11: 0+0j + iq_imbal12: 0+0j + iq_imbal13: 0+0j + iq_imbal14: 0+0j + iq_imbal15: 0+0j + iq_imbal16: 0+0j + iq_imbal17: 0+0j + iq_imbal18: 0+0j + iq_imbal19: 0+0j + iq_imbal2: 0+0j + iq_imbal20: 0+0j + iq_imbal21: 0+0j + iq_imbal22: 0+0j + iq_imbal23: 0+0j + iq_imbal24: 0+0j + iq_imbal25: 0+0j + iq_imbal26: 0+0j + iq_imbal27: 0+0j + iq_imbal28: 0+0j + iq_imbal29: 0+0j + iq_imbal3: 0+0j + iq_imbal30: 0+0j + iq_imbal31: 0+0j + iq_imbal4: 0+0j + iq_imbal5: 0+0j + iq_imbal6: 0+0j + iq_imbal7: 0+0j + iq_imbal8: 0+0j + iq_imbal9: 0+0j + iq_imbal_enb0: auto + iq_imbal_enb1: default + iq_imbal_enb10: default + iq_imbal_enb11: default + iq_imbal_enb12: default + iq_imbal_enb13: default + iq_imbal_enb14: default + iq_imbal_enb15: default + iq_imbal_enb16: default + iq_imbal_enb17: default + iq_imbal_enb18: default + iq_imbal_enb19: default + iq_imbal_enb2: default + iq_imbal_enb20: default + iq_imbal_enb21: default + iq_imbal_enb22: default + iq_imbal_enb23: default + iq_imbal_enb24: default + iq_imbal_enb25: default + iq_imbal_enb26: default + iq_imbal_enb27: default + iq_imbal_enb28: default + iq_imbal_enb29: default + iq_imbal_enb3: default + iq_imbal_enb30: default + iq_imbal_enb31: default + iq_imbal_enb4: default + iq_imbal_enb5: default + iq_imbal_enb6: default + iq_imbal_enb7: default + iq_imbal_enb8: default + iq_imbal_enb9: default + lo_export0: 'False' + lo_export1: 'False' + lo_export10: 'False' + lo_export11: 'False' + lo_export12: 'False' + lo_export13: 'False' + lo_export14: 'False' + lo_export15: 'False' + lo_export16: 'False' + lo_export17: 'False' + lo_export18: 'False' + lo_export19: 'False' + lo_export2: 'False' + lo_export20: 'False' + lo_export21: 'False' + lo_export22: 'False' + lo_export23: 'False' + lo_export24: 'False' + lo_export25: 'False' + lo_export26: 'False' + lo_export27: 'False' + lo_export28: 'False' + lo_export29: 'False' + lo_export3: 'False' + lo_export30: 'False' + lo_export31: 'False' + lo_export4: 'False' + lo_export5: 'False' + lo_export6: 'False' + lo_export7: 'False' + lo_export8: 'False' + lo_export9: 'False' + lo_source0: internal + lo_source1: internal + lo_source10: internal + lo_source11: internal + lo_source12: internal + lo_source13: internal + lo_source14: internal + lo_source15: internal + lo_source16: internal + lo_source17: internal + lo_source18: internal + lo_source19: internal + lo_source2: internal + lo_source20: internal + lo_source21: internal + lo_source22: internal + lo_source23: internal + lo_source24: internal + lo_source25: internal + lo_source26: internal + lo_source27: internal + lo_source28: internal + lo_source29: internal + lo_source3: internal + lo_source30: internal + lo_source31: internal + lo_source4: internal + lo_source5: internal + lo_source6: internal + lo_source7: internal + lo_source8: internal + lo_source9: internal + maxoutbuf: '0' + minoutbuf: '0' + nchan: '1' + num_mboards: '1' + otw: '' + rx_agc0: Default + rx_agc1: Default + rx_agc10: Default + rx_agc11: Default + rx_agc12: Default + rx_agc13: Default + rx_agc14: Default + rx_agc15: Default + rx_agc16: Default + rx_agc17: Default + rx_agc18: Default + rx_agc19: Default + rx_agc2: Default + rx_agc20: Default + rx_agc21: Default + rx_agc22: Default + rx_agc23: Default + rx_agc24: Default + rx_agc25: Default + rx_agc26: Default + rx_agc27: Default + rx_agc28: Default + rx_agc29: Default + rx_agc3: Default + rx_agc30: Default + rx_agc31: Default + rx_agc4: Default + rx_agc5: Default + rx_agc6: Default + rx_agc7: Default + rx_agc8: Default + rx_agc9: Default + samp_rate: samp_rate + sd_spec0: '' + sd_spec1: '' + sd_spec2: '' + sd_spec3: '' + sd_spec4: '' + sd_spec5: '' + sd_spec6: '' + sd_spec7: '' + show_lo_controls: 'False' + start_time: '-1.0' + stream_args: '' + stream_chans: '[]' + sync: pc_clock_next_pps + time_source0: '' + time_source1: '' + time_source2: '' + time_source3: '' + time_source4: '' + time_source5: '' + time_source6: '' + time_source7: '' + type: fc32 + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [328, 108.0] rotation: 0 state: true - name: xmlrpc_server_0 @@ -1171,7 +1631,7 @@ blocks: bus_sink: false bus_source: false bus_structure: null - coordinate: [935, 52] + coordinate: [1016, 84.0] rotation: 0 state: true - name: zeromq_pub_sink_0 @@ -1335,7 +1795,8 @@ connections: - [dc_blocker_xx_0, '0', blocks_skiphead_0, '0'] - [fft_vxx_0, '0', blocks_complex_to_mag_squared_0, '0'] - [osmosdr_source_0, '0', add_clock_tags, '0'] +- [uhd_usrp_source_1, '0', add_clock_tags, '0'] metadata: file_format: 1 - grc_version: 3.10.5.1 + grc_version: 3.10.5.0 diff --git a/radio/radio_process/radioonly.grc b/radio/radio_process/radioonly.grc index 0d27718d..3486591e 100644 --- a/radio/radio_process/radioonly.grc +++ b/radio/radio_process/radioonly.grc @@ -165,6 +165,30 @@ blocks: coordinate: [132, 282] rotation: 0 state: true +- name: rf_freq + id: variable + parameters: + comment: '' + value: freq + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [1080, 60.0] + rotation: 0 + state: enabled +- name: rf_gain + id: variable + parameters: + comment: '' + value: '20' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [1000, 60.0] + rotation: 0 + state: enabled - name: samp_rate id: variable parameters: @@ -1042,7 +1066,7 @@ blocks: bus_structure: null coordinate: [432, 172.0] rotation: 0 - state: true + state: disabled - name: qtgui_sink_x_0 id: qtgui_sink_x parameters: @@ -1294,6 +1318,442 @@ blocks: coordinate: [904, 836.0] rotation: 0 state: true +- name: usrp0 + id: uhd_usrp_source + parameters: + affinity: '' + alias: usrp0 + ant0: '"RX2"' + ant1: '"RX2"' + ant10: '"RX2"' + ant11: '"RX2"' + ant12: '"RX2"' + ant13: '"RX2"' + ant14: '"RX2"' + ant15: '"RX2"' + ant16: '"RX2"' + ant17: '"RX2"' + ant18: '"RX2"' + ant19: '"RX2"' + ant2: '"RX2"' + ant20: '"RX2"' + ant21: '"RX2"' + ant22: '"RX2"' + ant23: '"RX2"' + ant24: '"RX2"' + ant25: '"RX2"' + ant26: '"RX2"' + ant27: '"RX2"' + ant28: '"RX2"' + ant29: '"RX2"' + ant3: '"RX2"' + ant30: '"RX2"' + ant31: '"RX2"' + ant4: '"RX2"' + ant5: '"RX2"' + ant6: '"RX2"' + ant7: '"RX2"' + ant8: '"RX2"' + ant9: '"RX2"' + bw0: samp_rate + bw1: samp_rate + bw10: '0' + bw11: '0' + bw12: '0' + bw13: '0' + bw14: '0' + bw15: '0' + bw16: '0' + bw17: '0' + bw18: '0' + bw19: '0' + bw2: '0' + bw20: '0' + bw21: '0' + bw22: '0' + bw23: '0' + bw24: '0' + bw25: '0' + bw26: '0' + bw27: '0' + bw28: '0' + bw29: '0' + bw3: '0' + bw30: '0' + bw31: '0' + bw4: '0' + bw5: '0' + bw6: '0' + bw7: '0' + bw8: '0' + bw9: '0' + center_freq0: freq + center_freq1: freq + center_freq10: '0' + center_freq11: '0' + center_freq12: '0' + center_freq13: '0' + center_freq14: '0' + center_freq15: '0' + center_freq16: '0' + center_freq17: '0' + center_freq18: '0' + center_freq19: '0' + center_freq2: rf_freq + center_freq20: '0' + center_freq21: '0' + center_freq22: '0' + center_freq23: '0' + center_freq24: '0' + center_freq25: '0' + center_freq26: '0' + center_freq27: '0' + center_freq28: '0' + center_freq29: '0' + center_freq3: rf_freq + center_freq30: '0' + center_freq31: '0' + center_freq4: '0' + center_freq5: '0' + center_freq6: '0' + center_freq7: '0' + center_freq8: '0' + center_freq9: '0' + clock_rate: 0e0 + clock_source0: '' + clock_source1: '' + clock_source2: '' + clock_source3: '' + clock_source4: '' + clock_source5: '' + clock_source6: '' + clock_source7: '' + comment: '' + dc_offs0: 0+0j + dc_offs1: 0+0j + dc_offs10: 0+0j + dc_offs11: 0+0j + dc_offs12: 0+0j + dc_offs13: 0+0j + dc_offs14: 0+0j + dc_offs15: 0+0j + dc_offs16: 0+0j + dc_offs17: 0+0j + dc_offs18: 0+0j + dc_offs19: 0+0j + dc_offs2: 0+0j + dc_offs20: 0+0j + dc_offs21: 0+0j + dc_offs22: 0+0j + dc_offs23: 0+0j + dc_offs24: 0+0j + dc_offs25: 0+0j + dc_offs26: 0+0j + dc_offs27: 0+0j + dc_offs28: 0+0j + dc_offs29: 0+0j + dc_offs3: 0+0j + dc_offs30: 0+0j + dc_offs31: 0+0j + dc_offs4: 0+0j + dc_offs5: 0+0j + dc_offs6: 0+0j + dc_offs7: 0+0j + dc_offs8: 0+0j + dc_offs9: 0+0j + dc_offs_enb0: default + dc_offs_enb1: default + dc_offs_enb10: default + dc_offs_enb11: default + dc_offs_enb12: default + dc_offs_enb13: default + dc_offs_enb14: default + dc_offs_enb15: default + dc_offs_enb16: default + dc_offs_enb17: default + dc_offs_enb18: default + dc_offs_enb19: default + dc_offs_enb2: default + dc_offs_enb20: default + dc_offs_enb21: default + dc_offs_enb22: default + dc_offs_enb23: default + dc_offs_enb24: default + dc_offs_enb25: default + dc_offs_enb26: default + dc_offs_enb27: default + dc_offs_enb28: default + dc_offs_enb29: default + dc_offs_enb3: default + dc_offs_enb30: default + dc_offs_enb31: default + dc_offs_enb4: default + dc_offs_enb5: default + dc_offs_enb6: default + dc_offs_enb7: default + dc_offs_enb8: default + dc_offs_enb9: default + dev_addr: '"addr=172.25.14.11"' + dev_args: '' + gain0: rf_gain + gain1: rf_gain + gain10: '0' + gain11: '0' + gain12: '0' + gain13: '0' + gain14: '0' + gain15: '0' + gain16: '0' + gain17: '0' + gain18: '0' + gain19: '0' + gain2: rf_gain + gain20: '0' + gain21: '0' + gain22: '0' + gain23: '0' + gain24: '0' + gain25: '0' + gain26: '0' + gain27: '0' + gain28: '0' + gain29: '0' + gain3: rf_gain + gain30: '0' + gain31: '0' + gain4: '0' + gain5: '0' + gain6: '0' + gain7: '0' + gain8: '0' + gain9: '0' + gain_type0: default + gain_type1: default + gain_type10: default + gain_type11: default + gain_type12: default + gain_type13: default + gain_type14: default + gain_type15: default + gain_type16: default + gain_type17: default + gain_type18: default + gain_type19: default + gain_type2: default + gain_type20: default + gain_type21: default + gain_type22: default + gain_type23: default + gain_type24: default + gain_type25: default + gain_type26: default + gain_type27: default + gain_type28: default + gain_type29: default + gain_type3: default + gain_type30: default + gain_type31: default + gain_type4: default + gain_type5: default + gain_type6: default + gain_type7: default + gain_type8: default + gain_type9: default + iq_imbal0: 0+0j + iq_imbal1: 0+0j + iq_imbal10: 0+0j + iq_imbal11: 0+0j + iq_imbal12: 0+0j + iq_imbal13: 0+0j + iq_imbal14: 0+0j + iq_imbal15: 0+0j + iq_imbal16: 0+0j + iq_imbal17: 0+0j + iq_imbal18: 0+0j + iq_imbal19: 0+0j + iq_imbal2: 0+0j + iq_imbal20: 0+0j + iq_imbal21: 0+0j + iq_imbal22: 0+0j + iq_imbal23: 0+0j + iq_imbal24: 0+0j + iq_imbal25: 0+0j + iq_imbal26: 0+0j + iq_imbal27: 0+0j + iq_imbal28: 0+0j + iq_imbal29: 0+0j + iq_imbal3: 0+0j + iq_imbal30: 0+0j + iq_imbal31: 0+0j + iq_imbal4: 0+0j + iq_imbal5: 0+0j + iq_imbal6: 0+0j + iq_imbal7: 0+0j + iq_imbal8: 0+0j + iq_imbal9: 0+0j + iq_imbal_enb0: default + iq_imbal_enb1: default + iq_imbal_enb10: default + iq_imbal_enb11: default + iq_imbal_enb12: default + iq_imbal_enb13: default + iq_imbal_enb14: default + iq_imbal_enb15: default + iq_imbal_enb16: default + iq_imbal_enb17: default + iq_imbal_enb18: default + iq_imbal_enb19: default + iq_imbal_enb2: default + iq_imbal_enb20: default + iq_imbal_enb21: default + iq_imbal_enb22: default + iq_imbal_enb23: default + iq_imbal_enb24: default + iq_imbal_enb25: default + iq_imbal_enb26: default + iq_imbal_enb27: default + iq_imbal_enb28: default + iq_imbal_enb29: default + iq_imbal_enb3: default + iq_imbal_enb30: default + iq_imbal_enb31: default + iq_imbal_enb4: default + iq_imbal_enb5: default + iq_imbal_enb6: default + iq_imbal_enb7: default + iq_imbal_enb8: default + iq_imbal_enb9: default + lo_export0: 'False' + lo_export1: 'False' + lo_export10: 'False' + lo_export11: 'False' + lo_export12: 'False' + lo_export13: 'False' + lo_export14: 'False' + lo_export15: 'False' + lo_export16: 'False' + lo_export17: 'False' + lo_export18: 'False' + lo_export19: 'False' + lo_export2: 'False' + lo_export20: 'False' + lo_export21: 'False' + lo_export22: 'False' + lo_export23: 'False' + lo_export24: 'False' + lo_export25: 'False' + lo_export26: 'False' + lo_export27: 'False' + lo_export28: 'False' + lo_export29: 'False' + lo_export3: 'False' + lo_export30: 'False' + lo_export31: 'False' + lo_export4: 'False' + lo_export5: 'False' + lo_export6: 'False' + lo_export7: 'False' + lo_export8: 'False' + lo_export9: 'False' + lo_source0: internal + lo_source1: internal + lo_source10: internal + lo_source11: internal + lo_source12: internal + lo_source13: internal + lo_source14: internal + lo_source15: internal + lo_source16: internal + lo_source17: internal + lo_source18: internal + lo_source19: internal + lo_source2: external + lo_source20: internal + lo_source21: internal + lo_source22: internal + lo_source23: internal + lo_source24: internal + lo_source25: internal + lo_source26: internal + lo_source27: internal + lo_source28: internal + lo_source29: internal + lo_source3: external + lo_source30: internal + lo_source31: internal + lo_source4: internal + lo_source5: internal + lo_source6: internal + lo_source7: internal + lo_source8: internal + lo_source9: internal + maxoutbuf: '0' + minoutbuf: '0' + nchan: '1' + num_mboards: '1' + otw: '' + rx_agc0: Default + rx_agc1: Default + rx_agc10: Default + rx_agc11: Default + rx_agc12: Default + rx_agc13: Default + rx_agc14: Default + rx_agc15: Default + rx_agc16: Default + rx_agc17: Default + rx_agc18: Default + rx_agc19: Default + rx_agc2: Default + rx_agc20: Default + rx_agc21: Default + rx_agc22: Default + rx_agc23: Default + rx_agc24: Default + rx_agc25: Default + rx_agc26: Default + rx_agc27: Default + rx_agc28: Default + rx_agc29: Default + rx_agc3: Default + rx_agc30: Default + rx_agc31: Default + rx_agc4: Default + rx_agc5: Default + rx_agc6: Default + rx_agc7: Default + rx_agc8: Default + rx_agc9: Default + samp_rate: samp_rate + sd_spec0: '' + sd_spec1: '' + sd_spec2: '' + sd_spec3: '' + sd_spec4: '' + sd_spec5: '' + sd_spec6: '' + sd_spec7: '' + show_lo_controls: 'False' + start_time: '-1.0' + stream_args: '' + stream_chans: '[]' + sync: pc_clock_next_pps + time_source0: '' + time_source1: '' + time_source2: '' + time_source3: '' + time_source4: '' + time_source5: '' + time_source6: '' + time_source7: '' + type: fc32 + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [456, 188.0] + rotation: 0 + state: true connections: - [blocks_add_xx_0, '0', fft_vxx_0, '0'] @@ -1322,7 +1782,8 @@ connections: - [fft_vxx_0, '0', blocks_multiply_conjugate_cc_0, '0'] - [fft_vxx_0, '0', blocks_multiply_conjugate_cc_0, '1'] - [osmosdr_source_0, '0', dc_blocker_xx_0, '0'] +- [usrp0, '0', dc_blocker_xx_0, '0'] metadata: file_format: 1 - grc_version: 3.10.5.1 + grc_version: 3.10.5.0 diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 33b5f0e1..baef75f3 100644 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -6,7 +6,7 @@ # # GNU Radio Python Flow Graph # Title: radio_process -# GNU Radio version: 3.8.1.0 +# GNU Radio version: 3.10.5.0 from gnuradio import blocks import pmt @@ -20,24 +20,24 @@ from argparse import ArgumentParser from gnuradio.eng_arg import eng_float, intx from gnuradio import eng_notation +from gnuradio import uhd +import time from gnuradio import zeromq - -try: - import SimpleXMLRPCServer -except ModuleNotFoundError: - import xmlrpc.server as SimpleXMLRPCServer - +from xmlrpc.server import SimpleXMLRPCServer import threading -from . import add_clock_tags import math import numpy as np -import osmosdr +from . import add_clock_tags +#import osmosdr import time + + class radio_process(gr.top_block): + def __init__(self, num_bins=256, num_integrations=100000): - gr.top_block.__init__(self, "radio_process") + gr.top_block.__init__(self, "radio_process", catch_exceptions=True) ################################################## # Parameters @@ -48,26 +48,25 @@ def __init__(self, num_bins=256, num_integrations=100000): ################################################## # Variables ################################################## - self.sinc_sample_locations = sinc_sample_locations = np.arange( - -np.pi * 4 / 2.0, np.pi * 4 / 2.0, np.pi / num_bins - ) - self.sinc_samples = sinc_samples = np.sinc( - sinc_sample_locations / np.pi) + + self.sinc_sample_locations = sinc_sample_locations = np.arange(-np.pi*4/2.0, np.pi*4/2.0, np.pi/num_bins) + self.sinc_samples = sinc_samples = np.sinc(sinc_sample_locations/np.pi) + self.freq = freq = 1420000000 self.vlsr = vlsr = np.nan self.tsys = tsys = 171 self.tcal = tcal = 290 - self.tag_period = tag_period = num_bins * num_integrations + self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" - self.samp_rate = samp_rate = 2400000 + self.samp_rate = samp_rate = 2000000 + self.rf_gain = rf_gain = 20 + self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan self.is_running = is_running = False self.glon = glon = np.nan self.glat = glat = np.nan - self.freq = freq = 1420000000 self.fft_window = fft_window = window.blackmanharris(num_bins) - self.custom_window = custom_window = sinc_samples * \ - np.hamming(4 * num_bins) + self.custom_window = custom_window = sinc_samples*np.hamming(4*num_bins) self.cal_values = cal_values = np.repeat(np.nan, num_bins) self.cal_pwr = cal_pwr = 1 self.beam_switch = beam_switch = 0 @@ -75,173 +74,91 @@ def __init__(self, num_bins=256, num_integrations=100000): ################################################## # Blocks ################################################## - self.zeromq_pub_sink_2_0 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5561", 100, False, -1 - ) - self.zeromq_pub_sink_2 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5560", 100, True, -1 - ) - self.zeromq_pub_sink_1_0 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5562", 100, True, -1 - ) - self.zeromq_pub_sink_1 = zeromq.pub_sink( - gr.sizeof_float, num_bins, "tcp://127.0.0.1:5563", 100, False, -1 - ) - self.zeromq_pub_sink_0_0 = zeromq.pub_sink( - gr.sizeof_gr_complex, 1, "tcp://127.0.0.1:5559", 100, False, -1 - ) - self.zeromq_pub_sink_0 = zeromq.pub_sink( - gr.sizeof_gr_complex, 1, "tcp://127.0.0.1:5558", 100, True, -1 - ) - self.xmlrpc_server_0 = SimpleXMLRPCServer.SimpleXMLRPCServer( - ("localhost", 5557), allow_none=True - ) + self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True) + self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True) + self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True) + self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True) + self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True) + self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True) + self.xmlrpc_server_0 = SimpleXMLRPCServer(('localhost', 5557), allow_none=True) self.xmlrpc_server_0.register_instance(self) - self.xmlrpc_server_0_thread = threading.Thread( - target=self.xmlrpc_server_0.serve_forever - ) + self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) self.xmlrpc_server_0_thread.daemon = True self.xmlrpc_server_0_thread.start() - self.osmosdr_source_0 = osmosdr.source( - args="numchan=" + str(1) + " " + "soapy=0" - ) - self.osmosdr_source_0.set_time_unknown_pps(osmosdr.time_spec_t()) - self.osmosdr_source_0.set_sample_rate(samp_rate) - self.osmosdr_source_0.set_center_freq(freq, 0) - self.osmosdr_source_0.set_freq_corr(0, 0) - self.osmosdr_source_0.set_gain(49, 0) - self.osmosdr_source_0.set_if_gain(0, 0) - self.osmosdr_source_0.set_bb_gain(0, 0) - self.osmosdr_source_0.set_antenna("", 0) - self.osmosdr_source_0.set_bandwidth(0, 0) - self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) - self.dc_blocker_xx_0 = filter.dc_blocker_cc( - num_bins * num_integrations, False) - self.blocks_tags_strobe_0_0 = blocks.tags_strobe( - gr.sizeof_gr_complex * 1, - pmt.to_pmt( - { - "num_bins": num_bins, - "samp_rate": samp_rate, - "num_integrations": num_integrations, - "motor_az": motor_az, - "motor_el": motor_el, - "freq": freq, - "tsys": tsys, - "tcal": tcal, - "cal_pwr": cal_pwr, - "vlsr": vlsr, - "glat": glat, - "glon": glon, - "soutrack": soutrack, - "bsw": beam_switch, - } + self.uhd_usrp_source_1 = uhd.usrp_source( + ",".join(("addr=172.25.14.11", '')), + uhd.stream_args( + cpu_format="fc32", + args='', + channels=list(range(0,1)), ), - tag_period, - pmt.intern("metadata"), - ) - self.blocks_tags_strobe_0 = blocks.tags_strobe( - gr.sizeof_gr_complex * 1, - pmt.to_pmt(float(freq)), - tag_period, - pmt.intern("rx_freq"), - ) - self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins ) - self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins - ) - self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins - ) - self.blocks_stream_to_vector_0 = blocks.stream_to_vector( - gr.sizeof_gr_complex * 1, num_bins - ) - self.blocks_skiphead_0 = blocks.skiphead( - gr.sizeof_gr_complex * 1, num_bins * num_integrations - ) - self.blocks_selector_0 = blocks.selector( - gr.sizeof_gr_complex * 1, 0, 0) + + self.uhd_usrp_source_1.set_samp_rate(samp_rate) + _last_pps_time = self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() + # Poll get_time_last_pps() every 50 ms until a change is seen + while(self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() == _last_pps_time): + time.sleep(0.05) + # Set the time to PC time on next PPS + self.uhd_usrp_source_1.set_time_next_pps(uhd.time_spec(int(time.time()) + 1.0)) + # Sleep 1 second to ensure next PPS has come + time.sleep(1) + + self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) + self.uhd_usrp_source_1.set_antenna("RX2", 0) + self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) + self.uhd_usrp_source_1.set_gain(rf_gain, 0) + self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) + self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) + self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) + self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) + self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) + self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) + self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_stream_to_vector_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) + self.blocks_skiphead_0 = blocks.skiphead(gr.sizeof_gr_complex*1, (num_bins*num_integrations)) + self.blocks_selector_0 = blocks.selector(gr.sizeof_gr_complex*1,0,0) self.blocks_selector_0.set_enabled(True) - self.blocks_multiply_const_xx_0 = blocks.multiply_const_ff( - 1.0 / float(num_integrations), num_bins - ) - self.blocks_multiply_const_vxx_1 = blocks.multiply_const_vff( - [(tsys + tcal) / (value * cal_pwr) for value in cal_values] - ) - self.blocks_multiply_const_vxx_0_0_0_0 = blocks.multiply_const_vcc( - custom_window[0:num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0 = blocks.multiply_const_vcc( - custom_window[num_bins: 2 * num_bins] - ) - self.blocks_multiply_const_vxx_0_0 = blocks.multiply_const_vcc( - custom_window[2 * num_bins: 3 * num_bins] - ) - self.blocks_multiply_const_vxx_0 = blocks.multiply_const_vcc( - custom_window[-num_bins:] - ) - self.blocks_message_strobe_0 = blocks.message_strobe( - pmt.to_pmt(is_running), 100 - ) - self.blocks_integrate_xx_0 = blocks.integrate_ff( - num_integrations, num_bins) - self.blocks_delay_0_1 = blocks.delay( - gr.sizeof_gr_complex * 1, num_bins) - self.blocks_delay_0_0 = blocks.delay( - gr.sizeof_gr_complex * 1, num_bins * 2) - self.blocks_delay_0 = blocks.delay( - gr.sizeof_gr_complex * 1, num_bins * 3) - self.blocks_complex_to_mag_squared_0 = blocks.complex_to_mag_squared( - num_bins) + self.blocks_multiply_const_xx_0 = blocks.multiply_const_ff(1.0/float(num_integrations), num_bins) + self.blocks_multiply_const_vxx_1 = blocks.multiply_const_vff([(tsys + tcal)/(value * cal_pwr) for value in cal_values]) + self.blocks_multiply_const_vxx_0_0_0_0 = blocks.multiply_const_vcc(custom_window[0:num_bins]) + self.blocks_multiply_const_vxx_0_0_0 = blocks.multiply_const_vcc(custom_window[num_bins:2*num_bins]) + self.blocks_multiply_const_vxx_0_0 = blocks.multiply_const_vcc(custom_window[2*num_bins:3*num_bins]) + self.blocks_multiply_const_vxx_0 = blocks.multiply_const_vcc(custom_window[-num_bins:]) + self.blocks_message_strobe_0 = blocks.message_strobe(pmt.to_pmt(is_running), 100) + self.blocks_integrate_xx_0 = blocks.integrate_ff(num_integrations, num_bins) + self.blocks_delay_0_1 = blocks.delay(gr.sizeof_gr_complex*1, num_bins) + self.blocks_delay_0_0 = blocks.delay(gr.sizeof_gr_complex*1, (num_bins*2)) + self.blocks_delay_0 = blocks.delay(gr.sizeof_gr_complex*1, (num_bins*3)) + self.blocks_complex_to_mag_squared_0 = blocks.complex_to_mag_squared(num_bins) self.blocks_add_xx_0_0 = blocks.add_vcc(1) self.blocks_add_xx_0 = blocks.add_vcc(num_bins) self.add_clock_tags = add_clock_tags.clk(nsamps=tag_period) + ################################################## # Connections ################################################## self.connect((self.add_clock_tags, 0), (self.blocks_add_xx_0_0, 1)) self.connect((self.blocks_add_xx_0, 0), (self.fft_vxx_0, 0)) self.connect((self.blocks_add_xx_0_0, 0), (self.blocks_selector_0, 0)) - self.connect( - (self.blocks_complex_to_mag_squared_0, - 0), (self.blocks_integrate_xx_0, 0) - ) - self.connect((self.blocks_delay_0, 0), - (self.blocks_stream_to_vector_0_2, 0)) - self.connect((self.blocks_delay_0_0, 0), - (self.blocks_stream_to_vector_0_0, 0)) - self.connect((self.blocks_delay_0_1, 0), - (self.blocks_stream_to_vector_0_1, 0)) - self.connect( - (self.blocks_integrate_xx_0, 0), (self.blocks_multiply_const_xx_0, 0) - ) - self.connect((self.blocks_multiply_const_vxx_0, 0), - (self.blocks_add_xx_0, 0)) - self.connect((self.blocks_multiply_const_vxx_0_0, 0), - (self.blocks_add_xx_0, 1)) - self.connect( - (self.blocks_multiply_const_vxx_0_0_0, 0), (self.blocks_add_xx_0, 2) - ) - self.connect( - (self.blocks_multiply_const_vxx_0_0_0_0, 0), (self.blocks_add_xx_0, 3) - ) - self.connect((self.blocks_multiply_const_vxx_1, 0), - (self.zeromq_pub_sink_1, 0)) - self.connect( - (self.blocks_multiply_const_vxx_1, 0), (self.zeromq_pub_sink_1_0, 0) - ) - self.connect( - (self.blocks_multiply_const_xx_0, - 0), (self.blocks_multiply_const_vxx_1, 0) - ) - self.connect((self.blocks_multiply_const_xx_0, 0), - (self.zeromq_pub_sink_2, 0)) - self.connect( - (self.blocks_multiply_const_xx_0, 0), (self.zeromq_pub_sink_2_0, 0) - ) + self.connect((self.blocks_complex_to_mag_squared_0, 0), (self.blocks_integrate_xx_0, 0)) + self.connect((self.blocks_delay_0, 0), (self.blocks_stream_to_vector_0_2, 0)) + self.connect((self.blocks_delay_0_0, 0), (self.blocks_stream_to_vector_0_0, 0)) + self.connect((self.blocks_delay_0_1, 0), (self.blocks_stream_to_vector_0_1, 0)) + self.connect((self.blocks_integrate_xx_0, 0), (self.blocks_multiply_const_xx_0, 0)) + self.connect((self.blocks_multiply_const_vxx_0, 0), (self.blocks_add_xx_0, 0)) + self.connect((self.blocks_multiply_const_vxx_0_0, 0), (self.blocks_add_xx_0, 1)) + self.connect((self.blocks_multiply_const_vxx_0_0_0, 0), (self.blocks_add_xx_0, 2)) + self.connect((self.blocks_multiply_const_vxx_0_0_0_0, 0), (self.blocks_add_xx_0, 3)) + self.connect((self.blocks_multiply_const_vxx_1, 0), (self.zeromq_pub_sink_1, 0)) + self.connect((self.blocks_multiply_const_vxx_1, 0), (self.zeromq_pub_sink_1_0, 0)) + self.connect((self.blocks_multiply_const_xx_0, 0), (self.blocks_multiply_const_vxx_1, 0)) + self.connect((self.blocks_multiply_const_xx_0, 0), (self.zeromq_pub_sink_2, 0)) + self.connect((self.blocks_multiply_const_xx_0, 0), (self.zeromq_pub_sink_2_0, 0)) + self.connect((self.blocks_selector_0, 0), (self.dc_blocker_xx_0, 0)) self.connect((self.blocks_selector_0, 0), (self.zeromq_pub_sink_0, 0)) self.connect((self.blocks_selector_0, 0), @@ -249,32 +166,17 @@ def __init__(self, num_bins=256, num_integrations=100000): self.connect((self.blocks_skiphead_0, 0), (self.blocks_delay_0, 0)) self.connect((self.blocks_skiphead_0, 0), (self.blocks_delay_0_0, 0)) self.connect((self.blocks_skiphead_0, 0), (self.blocks_delay_0_1, 0)) - self.connect((self.blocks_skiphead_0, 0), - (self.blocks_stream_to_vector_0, 0)) - self.connect( - (self.blocks_stream_to_vector_0, - 0), (self.blocks_multiply_const_vxx_0, 0) - ) - self.connect( - (self.blocks_stream_to_vector_0_0, 0), - (self.blocks_multiply_const_vxx_0_0_0, 0), - ) - self.connect( - (self.blocks_stream_to_vector_0_1, 0), - (self.blocks_multiply_const_vxx_0_0, 0), - ) - self.connect( - (self.blocks_stream_to_vector_0_2, 0), - (self.blocks_multiply_const_vxx_0_0_0_0, 0), - ) - self.connect((self.blocks_tags_strobe_0, 0), - (self.blocks_add_xx_0_0, 0)) - self.connect((self.blocks_tags_strobe_0_0, 0), - (self.blocks_add_xx_0_0, 2)) + self.connect((self.blocks_skiphead_0, 0), (self.blocks_stream_to_vector_0, 0)) + self.connect((self.blocks_stream_to_vector_0, 0), (self.blocks_multiply_const_vxx_0, 0)) + self.connect((self.blocks_stream_to_vector_0_0, 0), (self.blocks_multiply_const_vxx_0_0_0, 0)) + self.connect((self.blocks_stream_to_vector_0_1, 0), (self.blocks_multiply_const_vxx_0_0, 0)) + self.connect((self.blocks_stream_to_vector_0_2, 0), (self.blocks_multiply_const_vxx_0_0_0_0, 0)) + self.connect((self.blocks_tags_strobe_0, 0), (self.blocks_add_xx_0_0, 0)) + self.connect((self.blocks_tags_strobe_0_0, 0), (self.blocks_add_xx_0_0, 2)) self.connect((self.dc_blocker_xx_0, 0), (self.blocks_skiphead_0, 0)) - self.connect((self.fft_vxx_0, 0), - (self.blocks_complex_to_mag_squared_0, 0)) - self.connect((self.osmosdr_source_0, 0), (self.add_clock_tags, 0)) + self.connect((self.fft_vxx_0, 0), (self.blocks_complex_to_mag_squared_0, 0)) + self.connect((self.uhd_usrp_source_1, 0), (self.add_clock_tags, 0)) + def get_num_bins(self): return self.num_bins @@ -282,181 +184,74 @@ def get_num_bins(self): def set_num_bins(self, num_bins): self.num_bins = num_bins self.set_cal_values(np.repeat(np.nan, self.num_bins)) - self.set_custom_window(self.sinc_samples * - np.hamming(4 * self.num_bins)) + self.set_custom_window(self.sinc_samples*np.hamming(4*self.num_bins)) self.set_fft_window(window.blackmanharris(self.num_bins)) - self.set_sinc_sample_locations( - np.arange(-np.pi * 4 / 2.0, np.pi * 4 / 2.0, np.pi / self.num_bins) - ) - self.set_tag_period(self.num_bins * self.num_integrations) - self.blocks_delay_0.set_dly(self.num_bins * 3) - self.blocks_delay_0_0.set_dly(self.num_bins * 2) - self.blocks_delay_0_1.set_dly(self.num_bins) - self.blocks_multiply_const_vxx_0.set_k( - self.custom_window[-self.num_bins:]) - self.blocks_multiply_const_vxx_0_0.set_k( - self.custom_window[2 * self.num_bins: 3 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0.set_k( - self.custom_window[self.num_bins: 2 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0_0.set_k( - self.custom_window[0: self.num_bins] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.set_sinc_sample_locations(np.arange(-np.pi*4/2.0, np.pi*4/2.0, np.pi/self.num_bins)) + self.set_tag_period(self.num_bins*self.num_integrations) + self.blocks_delay_0.set_dly(int((self.num_bins*3))) + self.blocks_delay_0_0.set_dly(int((self.num_bins*2))) + self.blocks_delay_0_1.set_dly(int(self.num_bins)) + self.blocks_multiply_const_vxx_0.set_k(self.custom_window[-self.num_bins:]) + self.blocks_multiply_const_vxx_0_0.set_k(self.custom_window[2*self.num_bins:3*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + def get_num_integrations(self): return self.num_integrations def set_num_integrations(self, num_integrations): self.num_integrations = num_integrations - self.set_tag_period(self.num_bins * self.num_integrations) - self.blocks_multiply_const_xx_0.set_k( - 1.0 / float(self.num_integrations)) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.set_tag_period(self.num_bins*self.num_integrations) + self.blocks_multiply_const_xx_0.set_k(1.0/float(self.num_integrations)) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_sinc_sample_locations(self): return self.sinc_sample_locations def set_sinc_sample_locations(self, sinc_sample_locations): self.sinc_sample_locations = sinc_sample_locations - self.set_sinc_samples(np.sinc(self.sinc_sample_locations / np.pi)) + self.set_sinc_samples(np.sinc(self.sinc_sample_locations/np.pi)) def get_sinc_samples(self): return self.sinc_samples def set_sinc_samples(self, sinc_samples): self.sinc_samples = sinc_samples - self.set_custom_window(self.sinc_samples * - np.hamming(4 * self.num_bins)) + self.set_custom_window(self.sinc_samples*np.hamming(4*self.num_bins)) + + def get_freq(self): + return self.freq + + def set_freq(self, freq): + self.freq = freq + self.set_rf_freq(self.freq) + self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_vlsr(self): return self.vlsr def set_vlsr(self, vlsr): self.vlsr = vlsr - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_tsys(self): return self.tsys def set_tsys(self, tsys): self.tsys = tsys - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_tcal(self): return self.tcal def set_tcal(self, tcal): self.tcal = tcal - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_tag_period(self): return self.tag_period @@ -472,105 +267,44 @@ def get_soutrack(self): def set_soutrack(self, soutrack): self.soutrack = soutrack - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_samp_rate(self): return self.samp_rate def set_samp_rate(self, samp_rate): self.samp_rate = samp_rate - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) - self.osmosdr_source_0.set_sample_rate(self.samp_rate) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.uhd_usrp_source_1.set_samp_rate(self.samp_rate) + self.uhd_usrp_source_1.set_bandwidth(self.samp_rate, 0) + + def get_rf_gain(self): + return self.rf_gain + + def set_rf_gain(self, rf_gain): + self.rf_gain = rf_gain + self.uhd_usrp_source_1.set_gain(self.rf_gain, 0) + + def get_rf_freq(self): + return self.rf_freq + + def set_rf_freq(self, rf_freq): + self.rf_freq = rf_freq + self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) def get_motor_el(self): return self.motor_el def set_motor_el(self, motor_el): self.motor_el = motor_el - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_motor_az(self): return self.motor_az def set_motor_az(self, motor_az): self.motor_az = motor_az - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_is_running(self): return self.is_running @@ -584,80 +318,14 @@ def get_glon(self): def set_glon(self, glon): self.glon = glon - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_glat(self): return self.glat def set_glat(self, glat): self.glat = glat - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) - - def get_freq(self): - return self.freq - - def set_freq(self, freq): - self.freq = freq - self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) - self.osmosdr_source_0.set_center_freq(self.freq, 0) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_fft_window(self): return self.fft_window @@ -670,114 +338,49 @@ def get_custom_window(self): def set_custom_window(self, custom_window): self.custom_window = custom_window - self.blocks_multiply_const_vxx_0.set_k( - self.custom_window[-self.num_bins:]) - self.blocks_multiply_const_vxx_0_0.set_k( - self.custom_window[2 * self.num_bins: 3 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0.set_k( - self.custom_window[self.num_bins: 2 * self.num_bins] - ) - self.blocks_multiply_const_vxx_0_0_0_0.set_k( - self.custom_window[0: self.num_bins] - ) + self.blocks_multiply_const_vxx_0.set_k(self.custom_window[-self.num_bins:]) + self.blocks_multiply_const_vxx_0_0.set_k(self.custom_window[2*self.num_bins:3*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) + self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) def get_cal_values(self): return self.cal_values def set_cal_values(self, cal_values): self.cal_values = cal_values - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) def get_cal_pwr(self): return self.cal_pwr def set_cal_pwr(self, cal_pwr): self.cal_pwr = cal_pwr - self.blocks_multiply_const_vxx_1.set_k( - [ - (self.tsys + self.tcal) / (value * self.cal_pwr) - for value in self.cal_values - ] - ) - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def get_beam_switch(self): return self.beam_switch def set_beam_switch(self, beam_switch): self.beam_switch = beam_switch - self.blocks_tags_strobe_0_0.set_value( - pmt.to_pmt( - { - "num_bins": self.num_bins, - "samp_rate": self.samp_rate, - "num_integrations": self.num_integrations, - "motor_az": self.motor_az, - "motor_el": self.motor_el, - "freq": self.freq, - "tsys": self.tsys, - "tcal": self.tcal, - "cal_pwr": self.cal_pwr, - "vlsr": self.vlsr, - "glat": self.glat, - "glon": self.glon, - "soutrack": self.soutrack, - "bsw": self.beam_switch, - } - ) - ) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) def argument_parser(): parser = ArgumentParser() parser.add_argument( - "--num-bins", - dest="num_bins", - type=intx, - default=256, - help="Set num_bins [default=%(default)r]", - ) + "--num-bins", dest="num_bins", type=intx, default=256, + help="Set num_bins [default=%(default)r]") parser.add_argument( - "--num-integrations", - dest="num_integrations", - type=intx, - default=100000, - help="Set num_integrations [default=%(default)r]", - ) + "--num-integrations", dest="num_integrations", type=intx, default=100000, + help="Set num_integrations [default=%(default)r]") return parser def main(top_block_cls=radio_process, options=None): if options is None: options = argument_parser().parse_args() - tb = top_block_cls( - num_bins=options.num_bins, num_integrations=options.num_integrations - ) + tb = top_block_cls(num_bins=options.num_bins, num_integrations=options.num_integrations) def sig_handler(sig=None, frame=None): tb.stop() @@ -793,5 +396,5 @@ def sig_handler(sig=None, frame=None): tb.wait() -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/srt/daemon/rotor_control/bigdish_client.py b/srt/daemon/rotor_control/bigdish_client.py new file mode 100755 index 00000000..149595c3 --- /dev/null +++ b/srt/daemon/rotor_control/bigdish_client.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python3 + +import time +import json +import threading +from websockets.sync.client import connect + +class BigDishClient: + def __init__(self, server_host, server_port, user, password, kick_others = False): + self.websocket = connect(f"ws://{server_host}:{server_port}") + self.message_id = 0 + self.websocket.send(json.dumps({"type": "auth", "id": self.message_id, "user": user, "password": password, "version": "0.0.1"})) + self.message_id += 1 + self.websocket.send(json.dumps({"type": "init", "id": self.message_id, "kick_others": kick_others})) + self.message_id += 1 + self.received_messages = {} + self._message_recv_thread_handle = threading.Thread(target = self._message_recv_thread) + self._message_recv_thread_handle.start() + + def _message_recv_thread(self): + for message in self.websocket: + message_decoded = json.loads(message) + self.received_messages[message_decoded["id"]] = message_decoded + + def _wait_for_response(self, id): + while True: + if id in self.received_messages: + message = self.received_messages[id] + del self.received_messages[id] + self.message_id += 1 + return message + time.sleep(0.01) + + def stow_pos(self): + self.websocket.send(json.dumps({"type": "stow_pos", "id": self.message_id})) + return self._wait_for_response(self.message_id) + + def goto_posvel_azel(self, az_pos, el_pos, az_vel, el_vel): + self.websocket.send(json.dumps({"type": "goto_posvel", "id": self.message_id, "coords": "azel", "az_pos": az_pos, "az_vel": az_vel, "el_pos": el_pos, "el_vel": el_vel})) + return self._wait_for_response(self.message_id) + + def track_radec(self, ra_pos, dec_pos, duration): + self.websocket.send(json.dumps({"type": "track", "id": self.message_id, "coords": "radec", "ra_pos": ra_pos, "dec_pos": dec_pos, "duration": duration})) + return self._wait_for_response(self.message_id) + + def track_gal(self, l_pos, b_pos, duration): + self.websocket.send(json.dumps({"type": "track", "id": self.message_id, "coords": "gal", "l_pos": l_pos, "b_pos": b_pos, "duration": duration})) + return self._wait_for_response(self.message_id) + + def get_posvel(self, coords, power): + self.websocket.send(json.dumps({"type": "get_posvel", "id": self.message_id, "coords": coords, "power": power})) + return self._wait_for_response(self.message_id) + +if __name__ == "__main__": + client = BigDishClient("localhost", 1234, "w1xm", "test", kick_others = True) + #while True: + # client.track_gal(162.592,4.5697, 5) + # time.sleep(1) diff --git a/srt/daemon/rotor_control/motors.py b/srt/daemon/rotor_control/motors.py index 24dddb0b..464959fe 100644 --- a/srt/daemon/rotor_control/motors.py +++ b/srt/daemon/rotor_control/motors.py @@ -9,6 +9,7 @@ from time import sleep from math import cos, acos, pi, sqrt, floor +from .bigdish_client import BigDishClient class Motor(ABC): """Abstract Class for All Motors Types @@ -793,3 +794,45 @@ def status(self): Current Azimuth and Elevation Coordinate as a Tuple of Floats """ return self.az, self.el + +class W1XMBigDishMotor(Motor): + """ + Class for Controlling the 54 roof Big Dish + """ + + def __init__(self): + """ + Initializer for W1XM Big Dish controller + """ + super().__init__(None, None, (0.0, 360.0), (0.0, 85.0)) + self.position = (60.0, 30.0) + self.client = BigDishClient("w1xm-radar-1.mitrs.org", 1234, "w1xm", "test", True) + + def point(self, az, el): + """Points the dish at a point + + Parameters + ---------- + az : float + Azimuth Coordinate to Point At + el : float + Elevation Coordinate to Point At + + Returns + ------- + None + """ + self.client.goto_posvel_azel(az, el, 0.0, 0.0) + self.position = (az, el) + + def status(self): + """Returns the Position of the Dish + + Returns + ------- + (float, float) + Current Azimuth and Elevation Coordinate as a Tuple of Floats + """ + pos = self.client.get_posvel("azel", False) + self.position = (pos["az_pos"], pos["el_pos"]) + return self.position diff --git a/srt/daemon/rotor_control/rotors.py b/srt/daemon/rotor_control/rotors.py index 04caaf0c..669ed69b 100644 --- a/srt/daemon/rotor_control/rotors.py +++ b/srt/daemon/rotor_control/rotors.py @@ -5,7 +5,7 @@ """ from enum import Enum -from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor +from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor, W1XMBigDishMotor def angle_within_range(angle, limits): @@ -25,6 +25,7 @@ class RotorType(Enum): ROT2 = "ALFASPID" H180 = "H180MOUNT" PUSH_ROD = "PUSHROD" + W1XM_BIG_DISH = "W1XMBIGDISH" class Rotor: @@ -58,6 +59,8 @@ def __init__(self, motor_type, port, baudrate, az_limits, el_limits): self.motor = H180Motor(port, baudrate, az_limits, el_limits) elif motor_type == RotorType.PUSH_ROD == RotorType.PUSH_ROD.value: self.motor = PushRodMotor(port, baudrate, az_limits, el_limits) + elif motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value: + self.motor = W1XMBigDishMotor() else: raise ValueError("Not a known motor type") From a5a1a8c88099a2561a7f3fa44ba2b77059171d2a Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 14 Feb 2024 01:24:41 +0000 Subject: [PATCH 24/79] Working on compatibility with big dish radar, plus bugfixes for original SRT code's tracking. changed bounds to trigger rotor position update from 0.5 degrees to 0.1 degrees. In practice this is somewhat sketchy and guarantees we average 50% of that offset over time. This should just be a periodic strobe and we should let the rotor controller decide whether or not to move. At minimum a future update should correct it to be relative to the antenna beamwidth --- config/config.yaml | 6 +++--- srt/daemon/daemon.py | 5 +++-- .../radio_control/radio_process/radio_process.py | 12 ++++++------ srt/daemon/rotor_control/motors.py | 2 +- srt/daemon/utilities/functions.py | 4 ++-- srt/dashboard/app.py | 12 +++++++----- 6 files changed, 22 insertions(+), 19 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index cf7f9dc5..703b48d3 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -34,14 +34,14 @@ MOTOR_BAUDRATE: 0 RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 -RADIO_NUM_BINS: 256 +RADIO_NUM_BINS: 512 RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 25 -BEAMWIDTH: 7.0 +BEAMWIDTH: 3.5 TSYS: 60 TCAL: 40 -SAVE_DIRECTORY: ~/Desktop/SRT-Saves +SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index d3d5dc65..8d4ca41c 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -192,8 +192,8 @@ def n_point_scan(self, object_id): scan_center = self.ephemeris_locations[object_id] np_sides = [5, 5] for scan in range(N_pnt_default): - self.log_message( - "{0} of {1} point scan.".format(scan, N_pnt_default)) + scan_center = self.ephemeris_locations[object_id] #recompute target position for every iteration + self.log_message("{0} of {1} point scan.".format(scan, N_pnt_default)) i = (scan // 5) - 2 j = (scan % 5) - 2 el_dif = i * self.beamwidth * 0.5 @@ -246,6 +246,7 @@ def beam_switch(self, object_id): rotor_loc = [] pwr_list = [] for j in range(0, 3 * self.num_beamswitches): + new_rotor_destination = self.ephemeris_locations[object_id] #recompute target position for every iteration self.radio_queue.put(("beam_switch", j + 1)) az_dif_scalar = np.cos(new_rotor_destination[1] * np.pi / 180.0) az_dif = (j % 3 - 1) * self.beamwidth / az_dif_scalar diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index baef75f3..0b670503 100644 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -28,7 +28,7 @@ import math import numpy as np from . import add_clock_tags -#import osmosdr +import osmosdr import time @@ -53,12 +53,12 @@ def __init__(self, num_bins=256, num_integrations=100000): self.sinc_samples = sinc_samples = np.sinc(sinc_sample_locations/np.pi) self.freq = freq = 1420000000 self.vlsr = vlsr = np.nan - self.tsys = tsys = 171 - self.tcal = tcal = 290 + self.tsys = tsys = 60 + self.tcal = tcal = 40 self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 - self.rf_gain = rf_gain = 20 + self.rf_gain = rf_gain = 25 self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan @@ -104,12 +104,12 @@ def __init__(self, num_bins=256, num_integrations=100000): # Sleep 1 second to ensure next PPS has come time.sleep(1) - self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) + self.uhd_usrp_source_1.set_center_freq(freq, 0) self.uhd_usrp_source_1.set_antenna("RX2", 0) self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) self.uhd_usrp_source_1.set_gain(rf_gain, 0) self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) - self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) + #self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) diff --git a/srt/daemon/rotor_control/motors.py b/srt/daemon/rotor_control/motors.py index 464959fe..36491b26 100644 --- a/srt/daemon/rotor_control/motors.py +++ b/srt/daemon/rotor_control/motors.py @@ -806,7 +806,7 @@ def __init__(self): """ super().__init__(None, None, (0.0, 360.0), (0.0, 85.0)) self.position = (60.0, 30.0) - self.client = BigDishClient("w1xm-radar-1.mitrs.org", 1234, "w1xm", "test", True) + self.client = BigDishClient("172.25.15.11", 1234, "w1xm", "test", True) def point(self, az, el): """Points the dish at a point diff --git a/srt/daemon/utilities/functions.py b/srt/daemon/utilities/functions.py index b044e4e3..1dfc5118 100644 --- a/srt/daemon/utilities/functions.py +++ b/srt/daemon/utilities/functions.py @@ -7,7 +7,7 @@ import numpy as np -def angle_within_range(actual_angle, desired_angle, bounds=0.5): +def angle_within_range(actual_angle, desired_angle, bounds=0.1): """Determines if Angles are Within a Threshold of One Another Parameters @@ -27,7 +27,7 @@ def angle_within_range(actual_angle, desired_angle, bounds=0.5): return abs(actual_angle - desired_angle) < bounds -def azel_within_range(actual_azel, desired_azel, bounds=(0.5, 0.5)): +def azel_within_range(actual_azel, desired_azel, bounds=(0.1, 0.1)): """Determines if AzEls are Within a Threshold of One Another Parameters diff --git a/srt/dashboard/app.py b/srt/dashboard/app.py index eaaa0ee6..1fff81a1 100644 --- a/srt/dashboard/app.py +++ b/srt/dashboard/app.py @@ -88,7 +88,9 @@ def generate_app(config_dir, config_dict): pio.templates.default = "seaborn" # Style Choice for Graphs curfold = Path(__file__).parent.absolute() # Generate Sidebar Objects - side_title = software + + side_title = "Medium Radio Telescope" + image_filename = curfold.joinpath( "images", "MIT_HO_logo_landscape.png" ) # replace with your own image @@ -272,7 +274,7 @@ def update_status_display(n): az_offset = el_offset = np.nan cf = np.nan bandwidth = np.nan - status_string = "SRT Not Connected" + status_string = "MRT Not Connected" vlsr = np.nan else: lat = status["location"]["latitude"] @@ -286,11 +288,11 @@ def update_status_display(n): vlsr = status["vlsr"] time_dif = time() - status["time"] if time_dif > 5: - status_string = "SRT Daemon Not Available" + status_string = "MRT Daemon Not Available" elif status["queue_size"] == 0 and status["queued_item"] == "None": - status_string = "SRT Inactive" + status_string = "MRT Inactive" else: - status_string = "SRT In Use!" + status_string = "MRT In Use!" if config_dict["SOFTWARE"] == "Very Small Radio Telescope": status_string = f""" From 36ebd2a524606d52ba299189681d28230282b91d Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Fri, 16 Feb 2024 17:55:37 -0500 Subject: [PATCH 25/79] move block tags strobe ahead of radio wait for pps --- .../radio_process/radio_process.py | 24 ++++++++++--------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 0b670503..dc25a851 100644 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -37,7 +37,7 @@ class radio_process(gr.top_block): def __init__(self, num_bins=256, num_integrations=100000): - gr.top_block.__init__(self, "radio_process", catch_exceptions=True) + gr.top_block.__init__(self, "radio_process") #, catch_exceptions=True) ################################################## # Parameters @@ -59,7 +59,7 @@ def __init__(self, num_bins=256, num_integrations=100000): self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 self.rf_gain = rf_gain = 25 - self.rf_freq = rf_freq = freq + #self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan self.is_running = is_running = False @@ -85,6 +85,9 @@ def __init__(self, num_bins=256, num_integrations=100000): self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) self.xmlrpc_server_0_thread.daemon = True self.xmlrpc_server_0_thread.start() + self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) + self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) + self.uhd_usrp_source_1 = uhd.usrp_source( ",".join(("addr=172.25.14.11", '')), uhd.stream_args( @@ -112,8 +115,6 @@ def __init__(self, num_bins=256, num_integrations=100000): #self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) - self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) - self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) @@ -226,10 +227,11 @@ def get_freq(self): def set_freq(self, freq): self.freq = freq - self.set_rf_freq(self.freq) + #self.set_rf_freq(self.freq) self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) - + self.uhd_usrp_source_1.set_center_freq(self.freq, 0) + def get_vlsr(self): return self.vlsr @@ -285,12 +287,12 @@ def set_rf_gain(self, rf_gain): self.rf_gain = rf_gain self.uhd_usrp_source_1.set_gain(self.rf_gain, 0) - def get_rf_freq(self): - return self.rf_freq + #def get_rf_freq(self): + # return self.rf_freq - def set_rf_freq(self, rf_freq): - self.rf_freq = rf_freq - self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) + #def set_rf_freq(self, rf_freq): + # self.rf_freq = rf_freq + # self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) def get_motor_el(self): return self.motor_el From d2e11ed90f24828129f3136fa30960d395ee52ae Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sun, 18 Feb 2024 00:04:31 +0000 Subject: [PATCH 26/79] modify dashboard to display raw n-point scan data and Fix axis scaling on npoint scan plot --- config/config.yaml | 2 +- srt/daemon/daemon.py | 10 +-- srt/dashboard/layouts/graphs.py | 106 +++++++++++++++++++++++++- srt/dashboard/layouts/monitor_page.py | 57 ++++++++++++-- 4 files changed, 162 insertions(+), 13 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 703b48d3..a9f5696e 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -37,7 +37,7 @@ RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 512 RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes -NUM_BEAMSWITCHES: 25 +NUM_BEAMSWITCHES: 10 BEAMWIDTH: 3.5 TSYS: 60 TCAL: 40 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 8d4ca41c..4ecdc4e6 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -167,7 +167,7 @@ def log_message(self, message): self.command_error_logs.append((time(), message)) print(message) - def n_point_scan(self, object_id): + def n_point_scan(self, object_id, grid_size=5): """Runs an N-Point (25) Scan About an Object Parameters @@ -185,17 +185,17 @@ def n_point_scan(self, object_id): cur_vlsr = self.ephemeris_vlsr[object_id] self.radio_queue.put(("vlsr", float(cur_vlsr))) self.current_vlsr = cur_vlsr - N_pnt_default = 25 + N_pnt_default = grid_size**2 rotor_loc = [] pwr_list = [] # scan_center = self.ephemeris_locations[object_id] - np_sides = [5, 5] + np_sides = [grid_size, grid_size] for scan in range(N_pnt_default): scan_center = self.ephemeris_locations[object_id] #recompute target position for every iteration self.log_message("{0} of {1} point scan.".format(scan, N_pnt_default)) - i = (scan // 5) - 2 - j = (scan % 5) - 2 + i = (scan // grid_size) - int(grid_size/2) + j = (scan % grid_size) - int(grid_size/2) el_dif = i * self.beamwidth * 0.5 az_dif_scalar = np.cos((scan_center[1] + el_dif) * np.pi / 180.0) # Avoid issues where you get close to the zenith diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index 981f549e..02846061 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -714,8 +714,110 @@ def emptygraph(xlabel, ylabel, title): return fig +def generate_npoint_raw(az_in, el_in, d_az, d_el, pow_in, cent, sides): + """Creates the n-point graph image with raw data without interpolation -def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides): + Parameters + ---------- + az_in : array_like + List of azimuth locations. + el_in : array_like + List of elevation locations. + d_az : float + Resolution of power measurements in the azimuth direction. + d_el : float + REsolution of power measurements in elevation direction. + pow_in : array_like + List of power measurements for the given locations of the antenna. + cent : array_like + Center point of the object being imaged. + sides : list + Number of pointers per side. + + Returns + ------- + fig : plotly.fig + Figure object. + """ + + # create the output grid + az_in = np.array(az_in) + el_in = np.array(el_in) + + idx_center = int(np.ceil(len(az_in)/2)) + az_center = az_in[idx_center] + el_center = el_in[idx_center] + + #az_span = (sides[0]-1)*d_az + #el_span = (sides[1]-1)*d_el + + az_range = np.linspace(az_center-d_az, az_center+d_az, sides[0]) + el_range = np.linspace(el_center-d_el, el_center+d_el, sides[1]) + + #below doesn't quite work because we are griddig a moving target + #az_range = np.linspace(az_in.min(), az_in.max(), sides[0]) + #el_range = np.linspace(el_in.min(), el_in.max(), sides[1]) + + #azout, elout = np.meshgrid(az_a, el_a) + pow_in = np.array(pow_in) + pow_grid = np.reshape(pow_in, (sides[0],sides[1])) + pmin = pow_in.min() + #p_in = pow_in - pmin + #x_l = np.linspace(-0.5, 0.5, sides[0]) + #y_l = np.linspace(-0.5, 0.5, sides[1]) + #xm, ym = np.meshgrid(x_l, y_l) + #xf = xm.flatten() + #yf = ym.flatten() + #xaout = np.linspace(-0.5, 0.5, 100) + #idxout = [(np.abs(xm - x_o)).argmin() for x_o in xaout] #get nearest neighboring point + #xo, yo = np.meshgrid(xaout, xaout) + #idxgrid, idygrid = np.meshgrid(idxout, idyout) + #idxf = idxgrid.flatten() + #idyf = idygrid.flatten() + #indices = np.transpose(np.array([idxf, idyf])) + # Interpolate the data + #interp_data_flat = pow_grid[indices] + #interp_data = np.reshape(interp_data_flat,(100,100)) + #interp_data = sinc_interp2d(xf, yf, p_in, d_az, d_el, xo, yo) + # Determine center of the object and compare to desired center. + #pow_tot = np.sum(np.sum(interp_data)) + #az_center = np.sum(np.sum(interp_data * azout)) / pow_tot + #el_center = np.sum(np.sum(interp_data * elout)) / pow_tot + #az_off = az_center - cent[0] + #el_off = el_center - cent[1] + #antext0 = "Az Center {0:.2f} deg".format(az_off) + #antext1 = "El Center {0:.2f} deg".format(el_off) + # Make the contour plot + d1 = go.Contour(z=pow_grid, x=az_range, y=el_range, colorscale="Viridis") + fig = go.Figure( + data=d1, + layout={ + "title": "Raw N-Point Scan", + "xaxis_title": "Azimuth Angle", + "yaxis_title": "Elevation Angle", + "uirevision": True, + }, + ) + #fig.add_annotation( + # x=xaout[10], + # y=xaout[20], + # xanchor="left", + # text=antext0, + # showarrow=False, + # font=dict(family="Courier New, monospace", size=13, color="#ffffff"), + #) + + #fig.add_annotation( + # x=xaout[10], + # y=xaout[10], + # text=antext1, + # xanchor="left", + # showarrow=False, + # font=dict(family="Courier New, monospace", size=13, color="#ffffff"), + #) + return fig + +def generate_npoint_interpolated(az_in, el_in, d_az, d_el, pow_in, cent, sides): """Creates the n-point graph image. Parameters @@ -773,7 +875,7 @@ def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides): fig = go.Figure( data=d1, layout={ - "title": "N-Point Scan", + "title": "N Point Sinc Interpolated", "xaxis_title": "Normalized x", "yaxis_title": "Normalized y", "uirevision": True, diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index ecc5ccf3..efc4062c 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -36,7 +36,8 @@ generate_power_history_graph, generate_spectrum_graph, generate_zoom_graph, - generate_npoint, + generate_npoint_raw, + generate_npoint_interpolated, emptygraph, ) @@ -125,9 +126,13 @@ def generate_npointlayout(): [ dcc.Store(id="npoint_info", storage_type="session"), html.Div( - [dcc.Graph(id="npoint-graph")], + [dcc.Graph(id="npoint-graph-1")], className="pretty_container six columns", ), + html.Div( + [dcc.Graph(id="npoint-graph-2")], + className="pretty_container six columns", + ), # html.Div( # [dcc.Graph(id="beamsswitch-graph")], # className="pretty_container six columns", @@ -967,11 +972,52 @@ def npointstore(n, npdata): raise PreventUpdate @app.callback( - Output("npoint-graph", "figure"), + Output("npoint-graph-1", "figure"), + [Input("npoint_info", "modified_timestamp")], + [State("npoint_info", "data")], + ) + def update_n_point_raw(ts, npdata): + """Update the npoint track info + + Parameters + ---------- + ts : int + modified time stamp + npdata : dict + will hold N- point data. + + Returns + ------- + ofig : plotly.fig + Plotly figure + """ + + if ts is None: + raise PreventUpdate + if npdata is None: + return emptygraph("x", "y", "N-Point Scan") + + if npdata.get("scan_center", [1, 1])[0] == 0: + return emptygraph("x", "y", "N-Point Scan") + + az_a = [] + el_a = [] + for irot in npdata["rotor_loc"]: + az_a.append(irot[0]) + el_a.append(irot[1]) + mdiff = npdata["maxdiff"] + sc = npdata["scan_center"] + plist = npdata["pwr"] + sd = npdata["sides"] + ofig = generate_npoint_raw(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) + return ofig + + @app.callback( + Output("npoint-graph-2", "figure"), [Input("npoint_info", "modified_timestamp")], [State("npoint_info", "data")], ) - def update_n_point(ts, npdata): + def update_n_point_interpolated(ts, npdata): """Update the npoint track info Parameters @@ -1004,8 +1050,9 @@ def update_n_point(ts, npdata): sc = npdata["scan_center"] plist = npdata["pwr"] sd = npdata["sides"] - ofig = generate_npoint(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) + ofig = generate_npoint_interpolated(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) return ofig + @app.callback( Output("start-warning", "children"), From 3d61928c72e6a62d806246555f53beab2130ca42 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Mon, 19 Feb 2024 01:46:12 +0000 Subject: [PATCH 27/79] add control to change number of points in N-point scan function --- config/config.yaml | 2 +- srt/daemon/daemon.py | 16 ++++++- srt/dashboard/layouts/graphs.py | 34 -------------- srt/dashboard/layouts/monitor_page.py | 64 +++++++++++++++++++++++++++ 4 files changed, 79 insertions(+), 37 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index a9f5696e..057dd760 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -40,7 +40,7 @@ RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 3.5 TSYS: 60 -TCAL: 40 +TCAL: 4.5 SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 4ecdc4e6..23e2918e 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -88,6 +88,7 @@ def __init__(self, config_directory, config_dict): self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] + self.npoints = 5 #default size of grid for npoint scan # Generate Default Calibration Values # Values are Set Up so that Uncalibrated and Calibrated Spectra are the Same Values @@ -210,7 +211,7 @@ def n_point_scan(self, object_id, grid_size=5): self.rotor_destination = scan_center self.point_at_offset(*new_rotor_offsets) rotor_loc.append(self.rotor_location) - sleep(5) + sleep(3) raw_spec = get_spectrum(port=5561) p = np.sum(raw_spec) a = len(raw_spec) @@ -449,6 +450,15 @@ def stop_recording(self): if self.radio_save_task is not None: self.radio_save_task.terminate() self.radio_save_task = None + + def set_npoints(self, n): + """Set the number of points for the N point scan + + Parameters + ---------- + npoints : number of points along grid edge for npoint scan + """ + self.npoints = n def set_freq(self, frequency): """Set the Frequency of the Processing Script @@ -815,7 +825,7 @@ def srt_daemon_main(self): # If Command Starts With a Valid Object Name if command_parts[0] in self.ephemeris_locations: if command_parts[-1] == "n": # N-Point Scan About Object - self.n_point_scan(object_id=command_parts[0]) + self.n_point_scan(object_id=command_parts[0], grid_size=self.npoints) elif command_parts[-1] == "b": # Beam-Switch Away From Object self.beam_switch(object_id=command_parts[0]) else: # Point Directly At Object @@ -826,6 +836,8 @@ def srt_daemon_main(self): self.point_at_azel(*self.cal_location) elif command_name == "calibrate": self.calibrate() + elif command_name == "npointset": + self.set_npoints(n=int(command_parts[1])) elif command_name == "quit": self.quit() elif command_name == "record": diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index 02846061..38b4918c 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -748,45 +748,11 @@ def generate_npoint_raw(az_in, el_in, d_az, d_el, pow_in, cent, sides): az_center = az_in[idx_center] el_center = el_in[idx_center] - #az_span = (sides[0]-1)*d_az - #el_span = (sides[1]-1)*d_el - az_range = np.linspace(az_center-d_az, az_center+d_az, sides[0]) el_range = np.linspace(el_center-d_el, el_center+d_el, sides[1]) - - #below doesn't quite work because we are griddig a moving target - #az_range = np.linspace(az_in.min(), az_in.max(), sides[0]) - #el_range = np.linspace(el_in.min(), el_in.max(), sides[1]) - #azout, elout = np.meshgrid(az_a, el_a) pow_in = np.array(pow_in) pow_grid = np.reshape(pow_in, (sides[0],sides[1])) - pmin = pow_in.min() - #p_in = pow_in - pmin - #x_l = np.linspace(-0.5, 0.5, sides[0]) - #y_l = np.linspace(-0.5, 0.5, sides[1]) - #xm, ym = np.meshgrid(x_l, y_l) - #xf = xm.flatten() - #yf = ym.flatten() - #xaout = np.linspace(-0.5, 0.5, 100) - #idxout = [(np.abs(xm - x_o)).argmin() for x_o in xaout] #get nearest neighboring point - #xo, yo = np.meshgrid(xaout, xaout) - #idxgrid, idygrid = np.meshgrid(idxout, idyout) - #idxf = idxgrid.flatten() - #idyf = idygrid.flatten() - #indices = np.transpose(np.array([idxf, idyf])) - # Interpolate the data - #interp_data_flat = pow_grid[indices] - #interp_data = np.reshape(interp_data_flat,(100,100)) - #interp_data = sinc_interp2d(xf, yf, p_in, d_az, d_el, xo, yo) - # Determine center of the object and compare to desired center. - #pow_tot = np.sum(np.sum(interp_data)) - #az_center = np.sum(np.sum(interp_data * azout)) / pow_tot - #el_center = np.sum(np.sum(interp_data * elout)) / pow_tot - #az_off = az_center - cent[0] - #el_off = el_center - cent[1] - #antext0 = "Az Center {0:.2f} deg".format(az_off) - #antext1 = "El Center {0:.2f} deg".format(el_off) # Make the contour plot d1 = go.Contour(z=pow_grid, x=az_range, y=el_range, colorscale="Viridis") fig = go.Figure( diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index efc4062c..b2df61ae 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -531,6 +531,41 @@ def generate_popups(software): ], id="point-modal", ), + dbc.Modal( + [ + dbc.ModalHeader("Enter the New N-point Grid Size"), + dbc.ModalBody( + [ + dcc.Input( + id="npoint-size", + type="number", + debounce=True, + placeholder="Grid Edge Points sqrt(N)", + style={"width": "100%"}, + ), + ] + ), + dbc.ModalFooter( + [ + dbc.Button( + "Yes", + id="npoint-set-btn-yes", + className="ml-auto", + # block=True, + color="primary", + ), + dbc.Button( + "No", + id="npoint-set-btn-no", + className="ml-auto", + # block=True, + color="secondary", + ), + ] + ), + ], + id="n-point-modal", + ), dbc.Modal( [ dbc.ModalHeader("Enter the New Center Frequency"), @@ -640,7 +675,9 @@ def generate_popups(software): ), ], id="offset-modal", + ), + dbc.Modal( [ dbc.ModalHeader("Start Recording"), @@ -806,6 +843,7 @@ def generate_layout(software): dbc.DropdownMenuItem("Stow", id="btn-stow"), dbc.DropdownMenuItem("Set AzEl", id="btn-point-azel"), dbc.DropdownMenuItem("Set Offsets", id="btn-set-offset"), + dbc.DropdownMenuItem("Set N-point size", id="btn-set-npoint"), ], "Radio": [ dbc.DropdownMenuItem("Set Frequency", id="btn-set-freq"), @@ -1352,6 +1390,32 @@ def point_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): if n_clicks_yes or n_clicks_no or n_clicks_btn: return not is_open return is_open + + + + @app.callback( + Output("n-point-modal", "is_open"), + [ + Input("btn-set-npoint", "n_clicks"), + Input("npoint-set-btn-yes", "n_clicks"), + Input("npoint-set-btn-no", "n_clicks"), + ], + [ + State("n-point-modal", "is_open"), + State("npoint-size", "value"), + ], + ) + def freq_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, npoints): + ctx = dash.callback_context + if not ctx.triggered: + return is_open + else: + button_id = ctx.triggered[0]["prop_id"].split(".")[0] + if button_id == "npoint-set-btn-yes": + command_thread.add_to_queue(f"npointset {npoints}") + if n_clicks_yes or n_clicks_no or n_clicks_btn: + return not is_open + return is_open @ app.callback( Output("freq-modal", "is_open"), From 1922ba95783ab72bad31f14deb5c737a0b6758b5 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 20 Feb 2024 02:17:23 +0000 Subject: [PATCH 28/79] add prototype functions for passthroughs for galactic and radec pointing with bigdish --- config/config.yaml | 4 +-- srt/daemon/daemon.py | 69 ++++++++++++++++++++++++++++++++++++++++++-- 2 files changed, 68 insertions(+), 5 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 057dd760..8a47f0b5 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -35,10 +35,10 @@ RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 512 -RADIO_INTEG_CYCLES: 10000 +RADIO_INTEG_CYCLES: 20000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 -BEAMWIDTH: 3.5 +BEAMWIDTH: 2.9 TSYS: 60 TCAL: 4.5 SAVE_DIRECTORY: /data/jlab diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 23e2918e..cbef97cd 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -211,7 +211,7 @@ def n_point_scan(self, object_id, grid_size=5): self.rotor_destination = scan_center self.point_at_offset(*new_rotor_offsets) rotor_loc.append(self.rotor_location) - sleep(3) + sleep(5) raw_spec = get_spectrum(port=5561) p = np.sum(raw_spec) a = len(raw_spec) @@ -330,8 +330,57 @@ def point_at_azel(self, az, el): while not azel_within_range(self.rotor_location, self.rotor_cmd_location): sleep(0.1) else: - self.log_message( - f"Object at {new_rotor_cmd_location} Not in Motor Bounds") + + self.log_message(f"Object at {new_rotor_cmd_location} Not in Motor Bounds") + + def point_at_galactic(self, l_pos, b_pos, duration): + """Points Antenna at a Specific Galactic longitude and lattitude + + Parameters + ---------- + l_pos : float + longitude, in degrees, to turn antenna towards + b_pos : float + lattitude, in degrees, to point antenna upwards at + duration : float + duration in seconds to continue tracking coordinate + + Returns + ------- + None + """ + + if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): + #rotor is smart enough to directly handle the command + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") + else: + #rotor needs command converted to az-el + self.log_message("direct galactic coordinate commands not yet supported for your rotor") + + def point_at_radec(self, ra_pos, dec_pos, duration): + """Points Antenna at a specific ICRS coordinate in Ra Dec + (Bigdish uses J2000) + + Parameters + ---------- + ra_pos : float + right ascension, in degrees, to turn antenna towards + dec_pos : float + declination, in degrees, to point antenna upwards at + duration : float + duration in seconds to continue tracking coordinate + + Returns + ------- + None + """ + + if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): + #rotor is smart enough to directly handle the command + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") + else: + #rotor needs command converted to az-el + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") def point_at_offset(self, az_off, el_off): """From the Current Object or Position Pointed At, Move to an Offset of That Location @@ -867,6 +916,20 @@ def srt_daemon_main(self): float(command_parts[1]), float(command_parts[2]), ) + #for bigdish enable temporary bypass of SRT command and control to directly point dish + elif command_name == "galactic": + self.point_at_galactic( + float(command_parts[1]), + float(command_parts[2]), + float(command_parts[3]), + ) + #for bigdish enable temporary bypass of SRT command and control to directly point dish + elif command_name == "radec": + self.point_at_radec( + float(command_parts[1]), + float(command_parts[2]), + float(command_parts[2]), + ) elif command_name == "offset": self.point_at_offset( float(command_parts[1]), float(command_parts[2]) From 08422cf5e9e96fafc29c48de6e7055eaeece70ba Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 20 Feb 2024 21:00:18 -0500 Subject: [PATCH 29/79] add messaging for the ettus radio to control noise calibrator functions and modify daemon to issue noise diode control commands to radio, plus various small fixes to radio flowgraph --- config/config.yaml | 5 +- config/schema.yaml | 1 + radio/radio_process/radio_process.grc | 113 +++++++++++++++++- radio/radio_save_spec/radio_save_spec.grc | 43 ++++--- srt/daemon/daemon.py | 32 +++++ .../calibrator_control_strobe.py | 64 ++++++++++ .../radio_process/radio_process.py | 112 ++++++++++------- 7 files changed, 303 insertions(+), 67 deletions(-) create mode 100644 srt/daemon/radio_control/radio_process/calibrator_control_strobe.py mode change 100644 => 100755 srt/daemon/radio_control/radio_process/radio_process.py diff --git a/config/config.yaml b/config/config.yaml index 8a47f0b5..3d6f95e7 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -35,12 +35,13 @@ RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 RADIO_NUM_BINS: 512 -RADIO_INTEG_CYCLES: 20000 +RADIO_INTEG_CYCLES: 10000 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 +CAL_TYPE: NOISE_DIODE TSYS: 60 -TCAL: 4.5 +TCAL: 40 SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 diff --git a/config/schema.yaml b/config/schema.yaml index 17ebcfd2..04cec7eb 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -17,6 +17,7 @@ RADIO_INTEG_CYCLES: int() RADIO_AUTOSTART: bool() NUM_BEAMSWITCHES: int() BEAMWIDTH: num() +CAL_TYPE: enum('COLD_SKY', 'NOISE_DIODE') TSYS: num() TCAL: num() SAVE_DIRECTORY: str() diff --git a/radio/radio_process/radio_process.grc b/radio/radio_process/radio_process.grc index 355838ac..8ddb734b 100644 --- a/radio/radio_process/radio_process.grc +++ b/radio/radio_process/radio_process.grc @@ -45,6 +45,18 @@ blocks: coordinate: [108, 398] rotation: 0 state: true +- name: cal_on + id: variable + parameters: + comment: '' + value: 'False' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [176, 468.0] + rotation: 0 + state: true - name: cal_pwr id: variable parameters: @@ -69,6 +81,18 @@ blocks: coordinate: [12, 594] rotation: 0 state: true +- name: calibrator_mask + id: variable + parameters: + comment: '' + value: '0b000000000011' + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [216, 380.0] + rotation: 0 + state: enabled - name: custom_window id: variable parameters: @@ -382,6 +406,7 @@ blocks: maxoutbuf: '0' minoutbuf: '0' num_ports: '1' + showports: 'False' type: complex vlen: '1' states: @@ -401,6 +426,7 @@ blocks: maxoutbuf: '0' minoutbuf: '0' num_ports: '1' + showports: 'False' type: complex vlen: '1' states: @@ -420,6 +446,7 @@ blocks: maxoutbuf: '0' minoutbuf: '0' num_ports: '1' + showports: 'False' type: complex vlen: '1' states: @@ -461,7 +488,7 @@ blocks: bus_sink: false bus_source: false bus_structure: null - coordinate: [823, 281] + coordinate: [800, 276.0] rotation: 0 state: true - name: blocks_multiply_const_vxx_0 @@ -719,7 +746,7 @@ blocks: value: 'pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, - "glon": glon, "soutrack": soutrack, "bsw": beam_switch})' + "glon": glon, "soutrack": soutrack, "bsw": beam_switch, "cal_on":cal_on})' vlen: '1' states: bus_sink: false @@ -728,6 +755,53 @@ blocks: coordinate: [548, 253] rotation: 0 state: true +- name: calibrator_control_strobe + id: epy_block + parameters: + _source_code: "\"\"\"\nblock to generate calibrator control commands for the X300\ + \ radio. \nnote that this block assumes a latency lower than the calibrator\ + \ cycle time\nand will break if that condition is not met\n\nEmbedded Python\ + \ Blocks:\n\nEach time this file is saved, GRC will instantiate the first class\ + \ it finds\nto get ports and parameters of your block. The arguments to __init__\ + \ will\nbe the parameters. All of them are required to have default values!\n\ + \"\"\"\nimport numpy as np\nfrom gnuradio import gr \nimport pmt\nimport time\n\ + import uhd\n\nclass msg_blk(gr.sync_block):\n def __init__(self, calibrator_mask=0xFFF,cal_state=False):\n\ + \ gr.sync_block.__init__(\n self,\n name=\"calibrator_msg_block\"\ + ,\n in_sig=None,\n out_sig=None\n )\n\n #input\ + \ parameters\n self.calibrator_mask = calibrator_mask\n self.cal_state\ + \ = cal_state\n\n #derived variables\n\n self.last_cal_state =\ + \ False\n \n self.message_port_register_in(pmt.intern('strobe'))\n\ + \ self.message_port_register_out(pmt.intern('command'))\n \n \ + \ self.set_msg_handler(pmt.intern('strobe'), self.handle_msg)\n\n def\ + \ handle_msg(self, msg):\n\n #send message to define next calibrator\ + \ state change\n\n if self.last_cal_state != self.cal_state:\n \ + \ if self.cal_state:\n new_cal_value = 0xFFF\n \ + \ else:\n new_cal_value = 0x000\n\n #issue command to\ + \ set toggle gpio\n\n set_gpio = pmt.make_dict()\n set_gpio =\ + \ pmt.dict_add(set_gpio, pmt.to_pmt('bank'), pmt.to_pmt('FP0A'))\n set_gpio\ + \ = pmt.dict_add(set_gpio, pmt.to_pmt('attr'), pmt.to_pmt('OUT'))\n set_gpio\ + \ = pmt.dict_add(set_gpio, pmt.to_pmt('value'), pmt.from_double(new_cal_value))\n\ + \ set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('mask'), pmt.from_double(self.calibrator_mask))\n\ + \n msg = pmt.make_dict()\n msg = pmt.dict_add(msg, pmt.to_pmt('gpio'),\ + \ set_gpio)\n\n self.message_port_pub(pmt.intern('command'), msg) #issue\ + \ message\n\n self.last_cal_state = self.cal_state\n\n " + affinity: '' + alias: '' + cal_state: cal_on + calibrator_mask: calibrator_mask + comment: '' + maxoutbuf: '0' + minoutbuf: '0' + states: + _io_cache: ('calibrator_msg_block', 'msg_blk', [('calibrator_mask', '4095'), ('cal_state', + 'False')], [('strobe', 'message', 1)], [('command', 'message', 1)], '', ['cal_state', + 'calibrator_mask']) + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [1080, 276.0] + rotation: 0 + state: true - name: dc_blocker_xx_0 id: dc_blocker_xx parameters: @@ -1184,11 +1258,34 @@ blocks: coordinate: [296, 92.0] rotation: 0 state: disabled +- name: snippet_0 + id: snippet + parameters: + alias: '' + code: 'calibrator_control_mask = self.calibrator_mask + + self.usrp0.set_gpio_attr(''FP0A'', ''CTRL'', 0x000, 0xFFF ^ calibrator_control_mask) #set + pins 2 and 3 manual + + self.usrp0.set_gpio_attr(''FP0A'', ''DDR'', 0xFFF, calibrator_control_mask) + #set pins 2 and 3 as output + + self.usrp0.set_gpio_attr(''FP0A'', ''OUT'', 0x000 , calibrator_control_mask)' + comment: '' + priority: '0' + section: main_after_init + states: + bus_sink: false + bus_source: false + bus_structure: null + coordinate: [200, 300.0] + rotation: 0 + state: true - name: uhd_usrp_source_1 id: uhd_usrp_source parameters: affinity: '' - alias: '' + alias: usrp0 ant0: '"RX2"' ant1: '"RX2"' ant10: '"RX2"' @@ -1640,6 +1737,7 @@ blocks: address: tcp://127.0.0.1:5558 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1661,6 +1759,7 @@ blocks: address: tcp://127.0.0.1:5559 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1682,6 +1781,7 @@ blocks: address: tcp://127.0.0.1:5563 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1703,6 +1803,7 @@ blocks: address: tcp://127.0.0.1:5562 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1724,6 +1825,7 @@ blocks: address: tcp://127.0.0.1:5560 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1745,6 +1847,7 @@ blocks: address: tcp://127.0.0.1:5561 affinity: '' alias: '' + bind: 'True' comment: '' drop_on_hwm: 'True' hwm: '-1' @@ -1770,6 +1873,7 @@ connections: - [blocks_delay_0_0, '0', blocks_stream_to_vector_0_0, '0'] - [blocks_delay_0_1, '0', blocks_stream_to_vector_0_1, '0'] - [blocks_integrate_xx_0, '0', blocks_multiply_const_xx_0, '0'] +- [blocks_message_strobe_0, strobe, calibrator_control_strobe, strobe] - [blocks_multiply_const_vxx_0, '0', blocks_add_xx_0, '0'] - [blocks_multiply_const_vxx_0_0, '0', blocks_add_xx_0, '1'] - [blocks_multiply_const_vxx_0_0_0, '0', blocks_add_xx_0, '2'] @@ -1792,6 +1896,7 @@ connections: - [blocks_stream_to_vector_0_2, '0', blocks_multiply_const_vxx_0_0_0_0, '0'] - [blocks_tags_strobe_0, '0', blocks_add_xx_0_0, '0'] - [blocks_tags_strobe_0_0, '0', blocks_add_xx_0_0, '2'] +- [calibrator_control_strobe, command, uhd_usrp_source_1, command] - [dc_blocker_xx_0, '0', blocks_skiphead_0, '0'] - [fft_vxx_0, '0', blocks_complex_to_mag_squared_0, '0'] - [osmosdr_source_0, '0', add_clock_tags, '0'] @@ -1799,4 +1904,4 @@ connections: metadata: file_format: 1 - grc_version: 3.10.5.0 + grc_version: 3.10.9.2 diff --git a/radio/radio_save_spec/radio_save_spec.grc b/radio/radio_save_spec/radio_save_spec.grc index c9273274..20d05d46 100644 --- a/radio/radio_save_spec/radio_save_spec.grc +++ b/radio/radio_save_spec/radio_save_spec.grc @@ -1,6 +1,7 @@ options: parameters: author: '' + catch_exceptions: 'True' category: '[GRC Hier Blocks]' cmake_opt: '' comment: '' @@ -125,25 +126,26 @@ blocks: \ = metadata[\"num_bins\"]\n tsys = metadata[\"tsys\"]\n tcal = metadata[\"\ tcal\"]\n cal_pwr = metadata[\"cal_pwr\"]\n vslr = metadata[\"vslr\"]\n\ \ glat = metadata[\"glat\"]\n glon = metadata[\"glon\"]\n soutrack\ - \ = metadata[\"soutrack\"]\n bsw = metadata[\"bsw\"]\n return (\n \ - \ motor_az,\n motor_el,\n freq / pow(10, 6),\n samp_rate\ - \ / pow(10, 6),\n num_integrations,\n num_bins,\n tsys,\n\ - \ tcal,\n cal_pwr,\n vslr,\n glat,\n glon,\n\ - \ soutrack,\n bsw,\n )\n\n\nclass blk(\n gr.sync_block\n\ - ): # other base classes are basic_block, decim_block, interp_block\n \"\"\ - \"Embedded Python Block example - a simple multiply const\"\"\"\n\n def __init__(\n\ - \ self, directory=\".\", filename=\"test.rad\", vec_length=4096\n \ - \ ): # only default arguments here\n \"\"\"arguments to this function\ - \ show up as parameters in GRC\"\"\"\n gr.sync_block.__init__(\n \ - \ self,\n name=\"Embedded Python Block\", # will show up\ - \ in GRC\n in_sig=[(np.float32, vec_length)],\n out_sig=None,\n\ - \ )\n # if an attribute with the same name as a parameter is found,\n\ - \ # a callback is registered (properties work, too).\n self.directory\ - \ = directory\n self.filename = filename\n self.vec_length = vec_length\n\ - \ self.obsn = 0\n\n def work(self, input_items, output_items):\n \ - \ \"\"\"example: multiply with constant\"\"\"\n file = open(pathlib.Path(self.directory,\ - \ self.filename), \"a+\")\n tags = self.get_tags_in_window(0, 0, len(input_items[0]))\n\ - \ latest_data_dict = {\n pmt.to_python(tag.key): pmt.to_python(tag.value)\ + \ = metadata[\"soutrack\"]\n bsw = metadata[\"bsw\"]\n cal_on = metadata[\"\ + cal_on\"]\n return (\n motor_az,\n motor_el,\n freq\ + \ / pow(10, 6),\n samp_rate / pow(10, 6),\n num_integrations,\n\ + \ num_bins,\n tsys,\n tcal,\n cal_pwr,\n \ + \ vslr,\n glat,\n glon,\n soutrack,\n bsw,\n \ + \ )\n\n\nclass blk(\n gr.sync_block\n): # other base classes are basic_block,\ + \ decim_block, interp_block\n \"\"\"Embedded Python Block example - a simple\ + \ multiply const\"\"\"\n\n def __init__(\n self, directory=\".\",\ + \ filename=\"test.rad\", vec_length=4096\n ): # only default arguments here\n\ + \ \"\"\"arguments to this function show up as parameters in GRC\"\"\"\ + \n gr.sync_block.__init__(\n self,\n name=\"Embedded\ + \ Python Block\", # will show up in GRC\n in_sig=[(np.float32, vec_length)],\n\ + \ out_sig=None,\n )\n # if an attribute with the same\ + \ name as a parameter is found,\n # a callback is registered (properties\ + \ work, too).\n self.directory = directory\n self.filename = filename\n\ + \ self.vec_length = vec_length\n self.obsn = 0\n\n def work(self,\ + \ input_items, output_items):\n \"\"\"example: multiply with constant\"\ + \"\"\n file = open(pathlib.Path(self.directory, self.filename), \"a+\"\ + )\n tags = self.get_tags_in_window(0, 0, len(input_items[0]))\n \ + \ latest_data_dict = {\n pmt.to_python(tag.key): pmt.to_python(tag.value)\ \ for tag in tags\n }\n yr, da, hr, mn, sc = parse_time(latest_data_dict[\"\ rx_time\"])\n (\n aznow,\n elnow,\n \ \ freq,\n bw,\n integ,\n nfreq,\n \ @@ -199,8 +201,10 @@ blocks: address: tcp://127.0.0.1:5562 affinity: '' alias: '' + bind: 'False' comment: '' hwm: '-1' + key: '' maxoutbuf: '0' minoutbuf: '0' pass_tags: 'True' @@ -220,3 +224,4 @@ connections: metadata: file_format: 1 + grc_version: 3.10.9.2 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index cbef97cd..2c8351e0 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -85,10 +85,13 @@ def __init__(self, config_directory, config_dict): self.radio_autostart = config_dict["RADIO_AUTOSTART"] self.num_beamswitches = config_dict["NUM_BEAMSWITCHES"] self.beamwidth = config_dict["BEAMWIDTH"] + self.cal_type = config_dict["CAL_TYPE"] self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] + self.npoints = 5 #default size of grid for npoint scan + self.radio_calibrator_state = False # Generate Default Calibration Values # Values are Set Up so that Uncalibrated and Calibrated Spectra are the Same Values @@ -430,6 +433,10 @@ def calibrate(self): ------- None """ + + self.set_calibrator_state(True) + sleep(0.1) + sleep( self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency ) @@ -446,6 +453,7 @@ def calibrate(self): self.cal_power = cal_data["cal_pwr"] self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) + self.set_calibrator_state(False) self.log_message("Calibration Done") def start_recording(self, name): @@ -573,6 +581,29 @@ def set_samp_rate(self, samp_rate): self.radio_save_task.terminate() self.radio_sample_frequency = samp_rate self.radio_queue.put(("samp_rate", self.radio_sample_frequency)) + + def set_calibrator_state(self, calibrator_state): + """Set the state of the calibrator via radio GPIO + + Note that this is highly system specific and must be programmed appropriately + + Parameters + ---------- + calibrator_state : boolean + whether the calibrator is on + + Returns + ------- + None + """ + if self.cal_type == "NOISE_DIODE": + #customize for appropriate control scheme + self.radio_calibrator_state = calibrator_state + self.radio_queue.put(("cal_on", self.radio_calibrator_state)) + + else: + self.log_message("Noise Source Not Implemented") + def quit(self): """Stops the Daemon Process @@ -755,6 +786,7 @@ def update_status(self): "n_point_data": self.n_point_data, "beam_switch_data": self.beam_switch_data, "time": time(), + "cal_state": self.radio_calibrator_state, } status_socket.send_json(status) sleep(0.5) diff --git a/srt/daemon/radio_control/radio_process/calibrator_control_strobe.py b/srt/daemon/radio_control/radio_process/calibrator_control_strobe.py new file mode 100644 index 00000000..cf2ba4a5 --- /dev/null +++ b/srt/daemon/radio_control/radio_process/calibrator_control_strobe.py @@ -0,0 +1,64 @@ +""" +block to generate calibrator control commands for the X300 radio. +note that this block assumes a latency lower than the calibrator cycle time +and will break if that condition is not met + +Embedded Python Blocks: + +Each time this file is saved, GRC will instantiate the first class it finds +to get ports and parameters of your block. The arguments to __init__ will +be the parameters. All of them are required to have default values! +""" +import numpy as np +from gnuradio import gr +import pmt +import time +import uhd + +class msg_blk(gr.sync_block): + def __init__(self, calibrator_mask=0xFFF,cal_state=False): + gr.sync_block.__init__( + self, + name="calibrator_msg_block", + in_sig=None, + out_sig=None + ) + + #input parameters + self.calibrator_mask = calibrator_mask + self.cal_state = cal_state + + #derived variables + + self.last_cal_state = False + #self.cal_value = 0x000 + + self.message_port_register_in(pmt.intern('strobe')) + self.message_port_register_out(pmt.intern('command')) + + self.set_msg_handler(pmt.intern('strobe'), self.handle_msg) + + def handle_msg(self, msg): + + #send message to define next calibrator state change + + if self.last_cal_state != self.cal_state: + if self.cal_state: + cal_value = 0xFFF + else: + cal_value = 0x000 + + #issue command to toggle gpio + set_gpio = pmt.make_dict() + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('bank'), pmt.to_pmt('FP0A')) + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('attr'), pmt.to_pmt('OUT')) + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('value'), pmt.from_double(cal_value)) + set_gpio = pmt.dict_add(set_gpio, pmt.to_pmt('mask'), pmt.from_double(self.calibrator_mask)) + + msg = pmt.make_dict() + msg = pmt.dict_add(msg, pmt.to_pmt('gpio'), set_gpio) + self.message_port_pub(pmt.intern('command'), msg) #issue message + + self.last_cal_state = self.cal_state + + #otherwise do nothing diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py old mode 100644 new mode 100755 index dc25a851..09b025ec --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -6,7 +6,7 @@ # # GNU Radio Python Flow Graph # Title: radio_process -# GNU Radio version: 3.10.5.0 +# GNU Radio version: 3.10.9.2 from gnuradio import blocks import pmt @@ -27,17 +27,16 @@ import threading import math import numpy as np +#import radio_process_add_clock_tags as add_clock_tags # embedded python block from . import add_clock_tags -import osmosdr -import time - - +#import radio_process_calibrator_control_strobe as calibrator_control_strobe # embedded python block +from . import calibrator_control_strobe class radio_process(gr.top_block): def __init__(self, num_bins=256, num_integrations=100000): - gr.top_block.__init__(self, "radio_process") #, catch_exceptions=True) + gr.top_block.__init__(self, "radio_process", catch_exceptions=True) ################################################## # Parameters @@ -53,13 +52,13 @@ def __init__(self, num_bins=256, num_integrations=100000): self.sinc_samples = sinc_samples = np.sinc(sinc_sample_locations/np.pi) self.freq = freq = 1420000000 self.vlsr = vlsr = np.nan - self.tsys = tsys = 60 - self.tcal = tcal = 40 + self.tsys = tsys = 171 + self.tcal = tcal = 290 self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 - self.rf_gain = rf_gain = 25 - #self.rf_freq = rf_freq = freq + self.rf_gain = rf_gain = 20 + self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan self.is_running = is_running = False @@ -67,27 +66,33 @@ def __init__(self, num_bins=256, num_integrations=100000): self.glat = glat = np.nan self.fft_window = fft_window = window.blackmanharris(num_bins) self.custom_window = custom_window = sinc_samples*np.hamming(4*num_bins) + self.calibrator_mask = calibrator_mask = 0b000000000011 self.cal_values = cal_values = np.repeat(np.nan, num_bins) self.cal_pwr = cal_pwr = 1 + self.cal_on = cal_on = False self.beam_switch = beam_switch = 0 ################################################## # Blocks ################################################## - self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True) - self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True) - self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True) - self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True) - self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True) - self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True) + + self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True, True) + self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True, True) + self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True, True) + self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True, True) + self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True, True) + self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True, True) self.xmlrpc_server_0 = SimpleXMLRPCServer(('localhost', 5557), allow_none=True) self.xmlrpc_server_0.register_instance(self) self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) self.xmlrpc_server_0_thread.daemon = True self.xmlrpc_server_0_thread.start() - self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch}), tag_period, pmt.intern("metadata")) + + #blocks_tags_strobe blocks need to come before slow radio startup commands + self.blocks_tags_strobe_0_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt({"num_bins": num_bins, "samp_rate": samp_rate, "num_integrations": num_integrations, "motor_az": motor_az, "motor_el": motor_el, "freq": freq, "tsys": tsys, "tcal": tcal, "cal_pwr": cal_pwr, "vlsr": vlsr, "glat": glat, "glon": glon, "soutrack": soutrack, "bsw": beam_switch, "cal_on": cal_on}), tag_period, pmt.intern("metadata")) self.blocks_tags_strobe_0 = blocks.tags_strobe(gr.sizeof_gr_complex*1, pmt.to_pmt(float(freq)), tag_period, pmt.intern("rx_freq")) + self.uhd_usrp_source_1 = uhd.usrp_source( ",".join(("addr=172.25.14.11", '')), uhd.stream_args( @@ -107,14 +112,21 @@ def __init__(self, num_bins=256, num_integrations=100000): # Sleep 1 second to ensure next PPS has come time.sleep(1) - self.uhd_usrp_source_1.set_center_freq(freq, 0) + self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) self.uhd_usrp_source_1.set_antenna("RX2", 0) self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) self.uhd_usrp_source_1.set_gain(rf_gain, 0) self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) - #self.uhd_usrp_source_1.set_auto_iq_balance(True, 0) + + ##### Manually Configure USRP GPIO + self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'CTRL', 0x000, 0xFFF ^ calibrator_mask) #set pins 2 and 3 manual + self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'DDR', 0xFFF, calibrator_mask) #set pins 2 and 3 as output + self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'OUT', 0x000 , calibrator_mask) + + self.fft_vxx_0 = fft.fft_vcc(num_bins, True, fft_window, True, 3) self.dc_blocker_xx_0 = filter.dc_blocker_cc((num_bins*num_integrations), False) + self.calibrator_control_strobe = calibrator_control_strobe.msg_blk(calibrator_mask=calibrator_mask, cal_state=cal_on) self.blocks_stream_to_vector_0_2 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_1 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, num_bins) @@ -142,6 +154,8 @@ def __init__(self, num_bins=256, num_integrations=100000): ################################################## # Connections ################################################## + self.msg_connect((self.blocks_message_strobe_0, 'strobe'), (self.calibrator_control_strobe, 'strobe')) + self.msg_connect((self.calibrator_control_strobe, 'command'), (self.uhd_usrp_source_1, 'command')) self.connect((self.add_clock_tags, 0), (self.blocks_add_xx_0_0, 1)) self.connect((self.blocks_add_xx_0, 0), (self.fft_vxx_0, 0)) self.connect((self.blocks_add_xx_0_0, 0), (self.blocks_selector_0, 0)) @@ -196,7 +210,7 @@ def set_num_bins(self, num_bins): self.blocks_multiply_const_vxx_0_0.set_k(self.custom_window[2*self.num_bins:3*self.num_bins]) self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_num_integrations(self): @@ -206,7 +220,7 @@ def set_num_integrations(self, num_integrations): self.num_integrations = num_integrations self.set_tag_period(self.num_bins*self.num_integrations) self.blocks_multiply_const_xx_0.set_k(1.0/float(self.num_integrations)) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_sinc_sample_locations(self): return self.sinc_sample_locations @@ -227,17 +241,16 @@ def get_freq(self): def set_freq(self, freq): self.freq = freq - #self.set_rf_freq(self.freq) + self.set_rf_freq(self.freq) self.blocks_tags_strobe_0.set_value(pmt.to_pmt(float(self.freq))) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) - self.uhd_usrp_source_1.set_center_freq(self.freq, 0) - + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) + def get_vlsr(self): return self.vlsr def set_vlsr(self, vlsr): self.vlsr = vlsr - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_tsys(self): return self.tsys @@ -245,7 +258,7 @@ def get_tsys(self): def set_tsys(self, tsys): self.tsys = tsys self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_tcal(self): return self.tcal @@ -253,7 +266,7 @@ def get_tcal(self): def set_tcal(self, tcal): self.tcal = tcal self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_tag_period(self): return self.tag_period @@ -269,14 +282,14 @@ def get_soutrack(self): def set_soutrack(self, soutrack): self.soutrack = soutrack - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_samp_rate(self): return self.samp_rate def set_samp_rate(self, samp_rate): self.samp_rate = samp_rate - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) self.uhd_usrp_source_1.set_samp_rate(self.samp_rate) self.uhd_usrp_source_1.set_bandwidth(self.samp_rate, 0) @@ -287,26 +300,26 @@ def set_rf_gain(self, rf_gain): self.rf_gain = rf_gain self.uhd_usrp_source_1.set_gain(self.rf_gain, 0) - #def get_rf_freq(self): - # return self.rf_freq + def get_rf_freq(self): + return self.rf_freq - #def set_rf_freq(self, rf_freq): - # self.rf_freq = rf_freq - # self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) + def set_rf_freq(self, rf_freq): + self.rf_freq = rf_freq + self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) def get_motor_el(self): return self.motor_el def set_motor_el(self, motor_el): self.motor_el = motor_el - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_motor_az(self): return self.motor_az def set_motor_az(self, motor_az): self.motor_az = motor_az - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_is_running(self): return self.is_running @@ -320,14 +333,14 @@ def get_glon(self): def set_glon(self, glon): self.glon = glon - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_glat(self): return self.glat def set_glat(self, glat): self.glat = glat - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def get_fft_window(self): return self.fft_window @@ -345,6 +358,13 @@ def set_custom_window(self, custom_window): self.blocks_multiply_const_vxx_0_0_0.set_k(self.custom_window[self.num_bins:2*self.num_bins]) self.blocks_multiply_const_vxx_0_0_0_0.set_k(self.custom_window[0:self.num_bins]) + def get_calibrator_mask(self): + return self.calibrator_mask + + def set_calibrator_mask(self, calibrator_mask): + self.calibrator_mask = calibrator_mask + self.calibrator_control_strobe.calibrator_mask = self.calibrator_mask + def get_cal_values(self): return self.cal_values @@ -358,14 +378,22 @@ def get_cal_pwr(self): def set_cal_pwr(self, cal_pwr): self.cal_pwr = cal_pwr self.blocks_multiply_const_vxx_1.set_k([(self.tsys + self.tcal)/(value * self.cal_pwr) for value in self.cal_values]) - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) + + def get_cal_on(self): + return self.cal_on + + def set_cal_on(self, cal_on): + self.cal_on = cal_on + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) + self.calibrator_control_strobe.cal_state = self.cal_on def get_beam_switch(self): return self.beam_switch def set_beam_switch(self, beam_switch): self.beam_switch = beam_switch - self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch})) + self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) def argument_parser(): @@ -383,7 +411,7 @@ def main(top_block_cls=radio_process, options=None): if options is None: options = argument_parser().parse_args() tb = top_block_cls(num_bins=options.num_bins, num_integrations=options.num_integrations) - + def sig_handler(sig=None, frame=None): tb.stop() tb.wait() From 78388e16d3e091a8cd15fd3999ae73dc497b3630 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 21 Feb 2024 03:57:56 +0000 Subject: [PATCH 30/79] Erase calibration values prior to running new cal. Additionally, add a 100ms delay before accesing file with saved calibration data to make absolutely certain it's not still being written to. This appears to fix an issue whereby the calibration sometimes gets garbled and produces a scrambled output plus fix command delays during cal --- config/config.yaml | 4 ++-- srt/daemon/daemon.py | 13 +++++++++++++ 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 3d6f95e7..c28271bc 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -40,8 +40,8 @@ RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 CAL_TYPE: NOISE_DIODE -TSYS: 60 -TCAL: 40 +TSYS: 60.0 +TCAL: 48.5 SAVE_DIRECTORY: /data/jlab RUN_HEADLESS: No DASHBOARD_PORT: 8080 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 2c8351e0..7f0a1dd7 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -434,7 +434,16 @@ def calibrate(self): None """ + # erase existing calibration + self.cal_values = [1.0 for _ in range(self.radio_num_bins)] + self.cal_power = 1.0 + + self.radio_queue.put(("cal_pwr", self.cal_power)) + self.radio_queue.put(("cal_values", self.cal_values)) + + #turn on calibration source (if we have one) self.set_calibrator_state(True) + sleep(0.1) sleep( @@ -446,6 +455,7 @@ def calibrate(self): ) radio_cal_task.start() radio_cal_task.join(30) + sleep(0.1) path = Path(self.config_directory, "calibration.json") with open(path, "r") as input_file: cal_data = json.load(input_file) @@ -453,6 +463,8 @@ def calibrate(self): self.cal_power = cal_data["cal_pwr"] self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) + + #disable calibration source and return self.set_calibrator_state(False) self.log_message("Calibration Done") @@ -600,6 +612,7 @@ def set_calibrator_state(self, calibrator_state): #customize for appropriate control scheme self.radio_calibrator_state = calibrator_state self.radio_queue.put(("cal_on", self.radio_calibrator_state)) + sleep(0.1) else: self.log_message("Noise Source Not Implemented") From 18c2f486ce8cdc6c800efcc6b4e01eefc6bd883a Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sun, 3 Mar 2024 01:12:58 +0000 Subject: [PATCH 31/79] added explicit calon and caloff commands to daemon to allow manual trigger of noise diodes Separated calibration controls into different gui dropdown and added direct noise source command buttons --- srt/daemon/daemon.py | 4 ++++ srt/dashboard/layouts/monitor_page.py | 18 +++++++++++++++--- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 7f0a1dd7..e330bfda 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -928,6 +928,10 @@ def srt_daemon_main(self): self.stow() elif command_name == "cal": self.point_at_azel(*self.cal_location) + elif command_name == "calon": + self.set_calibrator_state(True) + elif command_name == "caloff": + self.set_calibrator_state(False) elif command_name == "calibrate": self.calibrate() elif command_name == "npointset": diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index b2df61ae..a72601d1 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -849,10 +849,14 @@ def generate_layout(software): dbc.DropdownMenuItem("Set Frequency", id="btn-set-freq"), dbc.DropdownMenuItem("Set Bandwidth", id="btn-set-samp"), ], + "Calibration": [ + dbc.DropdownMenuItem("Calibrate", id="btn-calibrate"), + dbc.DropdownMenuItem("Noise Reference on", id="btn-calon"), + dbc.DropdownMenuItem("Noise Reference off", id="btn-caloff"), + ], "Routine": [ dbc.DropdownMenuItem("Start Recording", id="btn-start-record"), dbc.DropdownMenuItem("Stop Recording", id="btn-stop-record"), - dbc.DropdownMenuItem("Calibrate", id="btn-calibrate"), dbc.DropdownMenuItem("Upload CMD File", id="btn-cmd-file"), ], "Power": [ @@ -1600,18 +1604,22 @@ def run_srt_daemon(configuration_dir, configuration_dict): @ app.callback( Output("signal", "children"), [ - # Input("btn-stow", "n_clicks"), + Input("btn-stow", "n_clicks"), Input("btn-stop-record", "n_clicks"), Input("btn-quit", "n_clicks"), Input("btn-calibrate", "n_clicks"), + Input("btn-calon", "n_clicks"), + Input("btn-caloff", "n_clicks"), ], [State("recording-alert", "is_open")] ) def cmd_button_pressed( - # n_clicks_stow, + n_clicks_stow, n_clicks_stop_record, n_clicks_shutdown, n_clicks_calibrate, + n_clicks_calon, + n_clicks_caloff, is_open ): ctx = dash.callback_context @@ -1628,3 +1636,7 @@ def cmd_button_pressed( command_thread.add_to_queue("quit") elif button_id == "btn-calibrate": command_thread.add_to_queue("calibrate") + elif button_id == "btn-calon": + command_thread.add_to_queue("calon") + elif button_id == "btn-caloff": + command_thread.add_to_queue("caloff") From bc984f8134772af68b3bc9cb32c27914efb77c00 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sun, 3 Mar 2024 03:43:09 +0000 Subject: [PATCH 32/79] add calibrator state metadata to the .rad file output fixed .rad file export to not be broken currently does not save calibrator state but does now save file --- srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py | 1 + 1 file changed, 1 insertion(+) diff --git a/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py b/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py index 09e7c19e..b26b2f9d 100644 --- a/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py +++ b/srt/daemon/radio_control/radio_save_spec_rad/save_rad_file.py @@ -154,6 +154,7 @@ def work(self, input_items, output_items): glat, glon, soutrack, + ) start_line = start_format % ( istart * bw / nfreq + efflofreq, From a5448c0c35940982d9073aede0d24d3bd6bee82b Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 17 Sep 2024 02:37:02 +0000 Subject: [PATCH 33/79] added 10MHz and PPS lock commands at SDR startup to radio_process.py --- config/sky_coords.csv | 40 ++++++++++++++++++- .../radio_process/radio_process.py | 2 + 2 files changed, 40 insertions(+), 2 deletions(-) diff --git a/config/sky_coords.csv b/config/sky_coords.csv index 7c7a7d5e..ccad55f8 100644 --- a/config/sky_coords.csv +++ b/config/sky_coords.csv @@ -15,7 +15,7 @@ fk4,05 14 12,18 44 00,AC1 fk4,03 29 00,54 00 00,PULSAR fk4,08 30 00,-45 00 00,PS galactic,10,1,RC_CLOUD -galactic,00,0,G00 +galactic,0,0,G00 galactic,10,0,G10 galactic,20,0,G20 galactic,30,0,G30 @@ -50,4 +50,40 @@ galactic,310,0,G310 galactic,320,0,G320 galactic,330,0,G330 galactic,340,0,G340 -galactic,350,0,G350 \ No newline at end of file +galactic,350,0,G350 +galactic,5,0,G05 +galactic,15,0,G15 +galactic,25,0,G25 +galactic,35,0,G35 +galactic,45,0,G45 +galactic,55,0,G55 +galactic,65,0,G65 +galactic,75,0,G75 +galactic,85,0,G85 +galactic,95,0,G95 +galactic,105,0,G105 +galactic,115,0,G115 +galactic,125,0,G125 +galactic,135,0,G135 +galactic,145,0,G145 +galactic,155,0,G155 +galactic,165,0,G165 +galactic,175,0,G175 +galactic,185,0,G185 +galactic,195,0,G195 +galactic,205,0,G205 +galactic,215,0,G215 +galactic,225,0,G225 +galactic,235,0,G235 +galactic,245,0,G245 +galactic,255,0,G255 +galactic,265,0,G265 +galactic,275,0,G275 +galactic,285,0,G285 +galactic,295,0,G295 +galactic,305,0,G305 +galactic,315,0,G315 +galactic,325,0,G325 +galactic,335,0,G335 +galactic,345,0,G345 +galactic,355,0,G355 diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 09b025ec..a31a2443 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -103,6 +103,8 @@ def __init__(self, num_bins=256, num_integrations=100000): ) self.uhd_usrp_source_1.set_samp_rate(samp_rate) + self.uhd_usrp_source_1.set_clock_source("external") + self.uhd_usrp_source_1.set_time_source("external") _last_pps_time = self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() # Poll get_time_last_pps() every 50 ms until a change is seen while(self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() == _last_pps_time): From 21ba736132824aefcdd97b60d5b30bff5cebce38 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 17 Sep 2024 17:45:12 +0000 Subject: [PATCH 34/79] added offset tuning to remove DC spike and tweaked the gain a bit to try to reduce saturation by millstone Update daemon.py extend calibration delay to account for long filter settling period in radio process --- srt/daemon/daemon.py | 6 +++--- srt/daemon/radio_control/radio_process/radio_process.py | 6 ++++-- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index e330bfda..5a6d9800 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -447,7 +447,7 @@ def calibrate(self): sleep(0.1) sleep( - self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency + 4*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency ) radio_cal_task = RadioCalibrateTask( self.radio_num_bins, @@ -802,7 +802,7 @@ def update_status(self): "cal_state": self.radio_calibrator_state, } status_socket.send_json(status) - sleep(0.5) + sleep(0.1) def update_radio_settings(self): """Coordinates Sending XMLRPC Commands to the GNU Radio Script @@ -818,7 +818,7 @@ def update_radio_settings(self): method, value = self.radio_queue.get() call = getattr(rpc_server, f"set_{method}") call(value) - sleep(0.1) + sleep(0.01) def update_command_queue(self): """Waits for New Commands Coming in Over ZMQ PUSH/PULL diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index a31a2443..9dde2b20 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -57,7 +57,7 @@ def __init__(self, num_bins=256, num_integrations=100000): self.tag_period = tag_period = num_bins*num_integrations self.soutrack = soutrack = "at_stow" self.samp_rate = samp_rate = 2000000 - self.rf_gain = rf_gain = 20 + self.rf_gain = rf_gain = 10 self.rf_freq = rf_freq = freq self.motor_el = motor_el = np.nan self.motor_az = motor_az = np.nan @@ -294,6 +294,7 @@ def set_samp_rate(self, samp_rate): self.blocks_tags_strobe_0_0.set_value(pmt.to_pmt({"num_bins": self.num_bins, "samp_rate": self.samp_rate, "num_integrations": self.num_integrations, "motor_az": self.motor_az, "motor_el": self.motor_el, "freq": self.freq, "tsys": self.tsys, "tcal": self.tcal, "cal_pwr": self.cal_pwr, "vlsr": self.vlsr, "glat": self.glat, "glon": self.glon, "soutrack": self.soutrack, "bsw": self.beam_switch, "cal_on":self.cal_on})) self.uhd_usrp_source_1.set_samp_rate(self.samp_rate) self.uhd_usrp_source_1.set_bandwidth(self.samp_rate, 0) + self.uhd_usrp_source_1.set_center_freq(uhd.tune_request(self.rf_freq,self.samp_rate*0.6), 0) def get_rf_gain(self): return self.rf_gain @@ -307,7 +308,8 @@ def get_rf_freq(self): def set_rf_freq(self, rf_freq): self.rf_freq = rf_freq - self.uhd_usrp_source_1.set_center_freq(self.rf_freq, 0) + self.uhd_usrp_source_1.set_center_freq(uhd.tune_request(self.rf_freq,self.samp_rate*0.6), 0) + #self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) def get_motor_el(self): return self.motor_el From 21a168e5fea42a039d21032fd3923157ac07087f Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 17 Sep 2024 18:53:51 +0000 Subject: [PATCH 35/79] RF gain control added to daemon and dashboard initial RF gain added as a parameter in config --- config/config.yaml | 5 ++- config/schema.yaml | 1 + srt/daemon/daemon.py | 36 ++++++++++++++-- srt/dashboard/layouts/monitor_page.py | 60 +++++++++++++++++++++++++++ 4 files changed, 97 insertions(+), 5 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index c28271bc..5c47a3fe 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -34,8 +34,9 @@ MOTOR_BAUDRATE: 0 RADIO_CF: 1420000000 RADIO_SF: 2000000 RADIO_FREQ_CORR: 00000 +RADIO_RF_GAIN: 20 RADIO_NUM_BINS: 512 -RADIO_INTEG_CYCLES: 10000 +RADIO_INTEG_CYCLES: 8192 RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 @@ -47,4 +48,4 @@ RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 1000 +DASHBOARD_REFRESH_MS: 200 diff --git a/config/schema.yaml b/config/schema.yaml index 04cec7eb..9379525f 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -11,6 +11,7 @@ MOTOR_BAUDRATE: int() MOTOR_PORT: str() RADIO_CF: int() RADIO_SF: int() +RADIO_RF_GAIN: int() RADIO_FREQ_CORR: int() RADIO_NUM_BINS: int() RADIO_INTEG_CYCLES: int() diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 5a6d9800..41f2e4a0 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -79,6 +79,7 @@ def __init__(self, config_directory, config_dict): self.motor_baudrate = config_dict["MOTOR_BAUDRATE"] self.radio_center_frequency = config_dict["RADIO_CF"] self.radio_sample_frequency = config_dict["RADIO_SF"] + self.radio_rf_gain = config_dict["RADIO_RF_GAIN"] self.radio_frequency_correction = config_dict["RADIO_FREQ_CORR"] self.radio_num_bins = config_dict["RADIO_NUM_BINS"] self.radio_integ_cycles = config_dict["RADIO_INTEG_CYCLES"] @@ -593,6 +594,32 @@ def set_samp_rate(self, samp_rate): self.radio_save_task.terminate() self.radio_sample_frequency = samp_rate self.radio_queue.put(("samp_rate", self.radio_sample_frequency)) + + def set_rf_gain(self, rf_gain): + """Set the rf gain of the radio + + Note that this stops any currently running raw saving tasks + + Parameters + ---------- + rf_gain : float + rf_gain for the SDR in dB + + Returns + ------- + None + """ + if self.radio_save_task is not None: + self.radio_save_task.terminate() + #save old gain and cal values + #old_gain = self.radio_rf_gain + #old_cal_values = self.cal_values + + self.radio_rf_gain = rf_gain + #self.cal_values = old_cal_values* 10**(0.1*(old_gain - self.radio_rf_gain)) + + self.radio_queue.put(("rf_gain", self.radio_rf_gain)) + #self.radio_queue.put(("cal_values", self.cal_values)) def set_calibrator_state(self, calibrator_state): """Set the state of the calibrator via radio GPIO @@ -786,6 +813,7 @@ def update_status(self): "cal_loc": self.cal_location, "horizon_points": self.horizon_points, "center_frequency": self.radio_center_frequency, + "rf_gain": self.radio_rf_gain, "frequency_correction": self.radio_frequency_correction, "bandwidth": self.radio_sample_frequency, "motor_offsets": self.rotor_offsets, @@ -862,7 +890,7 @@ def srt_daemon_main(self): self.radio_process_task.start() except RuntimeError as e: self.log_message(str(e)) - sleep(5) + sleep(5) #wait a bit for the radio to actually start up # Send Settings to the GNU Radio Script radio_params = { @@ -871,6 +899,7 @@ def srt_daemon_main(self): self.radio_center_frequency + self.radio_frequency_correction, ), "Sample Rate": ("samp_rate", self.radio_sample_frequency), + "RF Gain": ("rf_gain", self.radio_rf_gain), "Motor Azimuth": ("motor_az", self.rotor_location[0]), "Motor Elevation": ("motor_el", self.rotor_location[1]), "Motor GalLat": ( @@ -949,8 +978,9 @@ def srt_daemon_main(self): self.set_freq(frequency=float( command_parts[1]) * pow(10, 6)) elif command_name == "samp": - self.set_samp_rate(samp_rate=float( - command_parts[1]) * pow(10, 6)) + self.set_samp_rate(samp_rate=float(command_parts[1]) * pow(10, 6)) + elif command_name == "rf_gain": + self.set_rf_gain(rf_gain=float(command_parts[1])) elif command_name == "coords": self.set_coords( float(command_parts[1]), float(command_parts[2])) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index a72601d1..28138012 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -636,6 +636,41 @@ def generate_popups(software): ], id="samp-modal", ), + dbc.Modal( + [ + dbc.ModalHeader("Enter the New RF Gain"), + dbc.ModalBody( + [ + dcc.Input( + id="rf_gain", + type="number", + debounce=True, + placeholder="RF Gain (dB)", + style={"width": "100%"}, + ), + ] + ), + dbc.ModalFooter( + [ + dbc.Button( + "Yes", + id="gain-btn-yes", + className="ml-auto", + # block=True, + color="primary", + ), + dbc.Button( + "No", + id="gain-btn-no", + className="ml-auto", + # block=True, + color="secondary", + ), + ] + ), + ], + id="gain-modal", + ), dbc.Modal( [ dbc.ModalHeader("Enter the Motor Offsets"), @@ -848,6 +883,7 @@ def generate_layout(software): "Radio": [ dbc.DropdownMenuItem("Set Frequency", id="btn-set-freq"), dbc.DropdownMenuItem("Set Bandwidth", id="btn-set-samp"), + dbc.DropdownMenuItem("Set RF Gain", id="btn-set-gain"), ], "Calibration": [ dbc.DropdownMenuItem("Calibrate", id="btn-calibrate"), @@ -1469,6 +1505,30 @@ def samp_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, samp): return not is_open return is_open + @app.callback( + Output("gain-modal", "is_open"), + [ + Input("btn-set-gain", "n_clicks"), + Input("gain-btn-yes", "n_clicks"), + Input("gain-btn-no", "n_clicks"), + ], + [ + State("gain-modal", "is_open"), + State("rf_gain", "value"), + ], + ) + def gain_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, gain): + ctx = dash.callback_context + if not ctx.triggered: + return is_open + else: + button_id = ctx.triggered[0]["prop_id"].split(".")[0] + if button_id == "gain-btn-yes": + command_thread.add_to_queue(f"rf_gain {gain}") + if n_clicks_yes or n_clicks_no or n_clicks_btn: + return not is_open + return is_open + @ app.callback( Output("offset-modal", "is_open"), [ From 551d0f97bf5e9323e83d4198b2240496fe63d8a0 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Wed, 18 Sep 2024 17:41:39 -0400 Subject: [PATCH 36/79] heavily modified calibration command to do initial file saves for a proper calibration approach --- config/config.yaml | 1 + config/schema.yaml | 1 + srt/daemon/daemon.py | 139 +++++++++++++++++++++++++++++++++++-------- 3 files changed, 117 insertions(+), 24 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index 5c47a3fe..e565b0d7 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -41,6 +41,7 @@ RADIO_AUTOSTART: Yes NUM_BEAMSWITCHES: 10 BEAMWIDTH: 2.9 CAL_TYPE: NOISE_DIODE +CAL_INTEGRATION_CYCLES: 5 TSYS: 60.0 TCAL: 48.5 SAVE_DIRECTORY: /data/jlab diff --git a/config/schema.yaml b/config/schema.yaml index 9379525f..1fe7be41 100644 --- a/config/schema.yaml +++ b/config/schema.yaml @@ -19,6 +19,7 @@ RADIO_AUTOSTART: bool() NUM_BEAMSWITCHES: int() BEAMWIDTH: num() CAL_TYPE: enum('COLD_SKY', 'NOISE_DIODE') +CAL_INTEGRATION_CYCLES: int() TSYS: num() TCAL: num() SAVE_DIRECTORY: str() diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 41f2e4a0..ab9202a7 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -11,6 +11,7 @@ from xmlrpc.client import ServerProxy from pathlib import Path from operator import add +import os import zmq import json @@ -87,6 +88,7 @@ def __init__(self, config_directory, config_dict): self.num_beamswitches = config_dict["NUM_BEAMSWITCHES"] self.beamwidth = config_dict["BEAMWIDTH"] self.cal_type = config_dict["CAL_TYPE"] + self.cal_cycles = config_dict["CAL_INTEGRATION_CYCLES"] self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] @@ -434,6 +436,11 @@ def calibrate(self): ------- None """ + + #kill any running file save operations since we're about to scramble them + + if self.radio_save_task is not None: + self.radio_save_task.terminate() # erase existing calibration self.cal_values = [1.0 for _ in range(self.radio_num_bins)] @@ -441,32 +448,116 @@ def calibrate(self): self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) - - #turn on calibration source (if we have one) - self.set_calibrator_state(True) - - sleep(0.1) - - sleep( - 4*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency - ) - radio_cal_task = RadioCalibrateTask( - self.radio_num_bins, - self.config_directory, - ) - radio_cal_task.start() - radio_cal_task.join(30) - sleep(0.1) + + ''' + simple cold sky cal for the basic SRT + ''' + + if self.cal_type == "COLD_SKY": + #define filenames for calibration measurements + cold_sky_name = "cold_sky.fits" + + #erase prior calibration files if present + cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) + if os.path.exists(cold_sky_file): + os.remove(cold_sky_file) + + #start saving new calibration file + self.radio_save_task = RadioSaveSpecFitsTask( + self.radio_sample_frequency, + self.radio_num_bins, + self.config_directory, + cold_sky_name, + ) + self.radio_save_task.start() + + sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + self.stop_recording() + + #### + + #goto calibration calculation program + + ''' + if we have a noise diode to use for calibration we need to make multiple measurements + ''' + + if self.cal_type == "NOISE_DIODE": + #define filenames for calibration measurements + cold_sky_name = "cold_sky.fits" + cal_ref_name = "cold_sky_plus_cal.fits" + + #erase prior calibration files if present + cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) + cal_ref_file=str(Path(config_directory, cal_ref_name).absolute()) + + if os.path.exists(cold_sky_file): + os.remove(cold_sky_file) + + if os.path.exists(cal_ref_file): + os.remove(cal_ref_file) + + #enable calibrator and wait for the idiotically long settling time the filters currently have + #(need to fix that eventually so integration intervals are fully independent like they should be) + + self.set_calibrator_state(True) + sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + + #save new cold sky calibration file + self.radio_save_task = RadioSaveSpecFitsTask( + self.radio_sample_frequency, + self.radio_num_bins, + self.config_directory, + cold_sky_name, + ) + self.radio_save_task.start() + + sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + self.stop_recording() + + #disable calibrator and wait for the idiotically long settling time the filters currently have + #(need to fix that eventually so integration intervals are fully independent like they should be) + + self.set_calibrator_state(False) + sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + + #save new calibration reference file + self.radio_save_task = RadioSaveSpecFitsTask( + self.radio_sample_frequency, + self.radio_num_bins, + self.config_directory, + cold_sky_name, + ) + self.radio_save_task.start() + + sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + self.stop_recording() + + + + #radio_cal_task = RadioCalibrateTask( + # self.radio_num_bins, + # self.config_directory, + # ) + # radio_cal_task.start() + # radio_cal_task.join(30) + # sleep(0.1) + + cal_data = { + "cal_values": self.cal_values, + "cal_powers": self.cal_powers + } + path = Path(self.config_directory, "calibration.json") - with open(path, "r") as input_file: - cal_data = json.load(input_file) - self.cal_values = cal_data["cal_values"] - self.cal_power = cal_data["cal_pwr"] + with open(path, "w") as input_file: + json.dump(cal_data, input_file) self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) - - #disable calibration source and return - self.set_calibrator_state(False) + + # #disable calibration source and return self.log_message("Calibration Done") def start_recording(self, name): @@ -639,7 +730,7 @@ def set_calibrator_state(self, calibrator_state): #customize for appropriate control scheme self.radio_calibrator_state = calibrator_state self.radio_queue.put(("cal_on", self.radio_calibrator_state)) - sleep(0.1) + #sleep(0.1) else: self.log_message("Noise Source Not Implemented") From 744a98b52b6acbad8c2580bd7147f3bd8683d68a Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 17:58:28 -0400 Subject: [PATCH 37/79] fixing thing the git rebase lost --- srt/daemon/daemon.py | 107 ++++++++---------- srt/daemon/utilities/calibration_functions.py | 72 ++++++++++++ 2 files changed, 122 insertions(+), 57 deletions(-) create mode 100644 srt/daemon/utilities/calibration_functions.py diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index ab9202a7..98cad7f8 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -27,6 +27,7 @@ ) from .utilities.object_tracker import EphemerisTracker from .utilities.functions import azel_within_range, get_spectrum +from .utilities.calibration_functions import basic_cold_sky_calibration_fit, additive_noise_calibration_fit class SmallRadioTelescopeDaemon: @@ -458,26 +459,25 @@ def calibrate(self): cold_sky_name = "cold_sky.fits" #erase prior calibration files if present - cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) + cold_sky_file=str(Path(self.config_directory, cold_sky_name).absolute()) if os.path.exists(cold_sky_file): os.remove(cold_sky_file) + self.log_message("Starting cold calibration reference measurement") + #start saving new calibration file - self.radio_save_task = RadioSaveSpecFitsTask( - self.radio_sample_frequency, - self.radio_num_bins, - self.config_directory, - cold_sky_name, - ) - self.radio_save_task.start() + sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + self.start_recording(name=cold_sky_name, file_dir=self.config_dir) + sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) + self.stop_recording() - sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + + ### compute calibration corrections + + cal_values, cal_power = basic_cold_sky_calibration_fit(cold_sky_file, self.temp_sys, self.temp_cal, 20) - self.stop_recording() - #### - #goto calibration calculation program ''' if we have a noise diode to use for calibration we need to make multiple measurements @@ -489,8 +489,8 @@ def calibrate(self): cal_ref_name = "cold_sky_plus_cal.fits" #erase prior calibration files if present - cold_sky_file=str(Path(config_directory, cold_sky_name).absolute()) - cal_ref_file=str(Path(config_directory, cal_ref_name).absolute()) + cold_sky_file=str(Path(self.config_directory, cold_sky_name).absolute()) + cal_ref_file=str(Path(self.config_directory, cal_ref_name).absolute()) if os.path.exists(cold_sky_file): os.remove(cold_sky_file) @@ -501,66 +501,60 @@ def calibrate(self): #enable calibrator and wait for the idiotically long settling time the filters currently have #(need to fix that eventually so integration intervals are fully independent like they should be) + self.log_message("Starting hot calibration reference measurement") + self.set_calibrator_state(True) sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) - - #save new cold sky calibration file - self.radio_save_task = RadioSaveSpecFitsTask( - self.radio_sample_frequency, - self.radio_num_bins, - self.config_directory, - cold_sky_name, - ) - self.radio_save_task.start() - - sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) - + self.start_recording(name=cal_ref_name, file_dir=self.config_directory) + sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) self.stop_recording() #disable calibrator and wait for the idiotically long settling time the filters currently have #(need to fix that eventually so integration intervals are fully independent like they should be) + self.log_message("Starting cold calibration reference measurement") + self.set_calibrator_state(False) sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) + self.start_recording(name=cold_sky_name, file_dir=self.config_directory) + sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) + self.stop_recording() - #save new calibration reference file - self.radio_save_task = RadioSaveSpecFitsTask( - self.radio_sample_frequency, - self.radio_num_bins, - self.config_directory, - cold_sky_name, - ) - self.radio_save_task.start() - - sleep((self.cal_cycles+1)*self.radio_num_bins/ self.radio_sample_frequency) + cal_values, cal_power = additive_noise_calibration_fit(cold_sky_file, cal_ref_file, self.temp_sys, self.temp_cal, 20) - self.stop_recording() + #erase old cal file to prevent wierdness + calibration_path = Path(self.config_directory, "calibration.json") + if os.path.exists(calibration_path): + os.remove(calibration_path) - #radio_cal_task = RadioCalibrateTask( - # self.radio_num_bins, - # self.config_directory, - # ) - # radio_cal_task.start() - # radio_cal_task.join(30) - # sleep(0.1) + #save result - cal_data = { - "cal_values": self.cal_values, - "cal_powers": self.cal_powers + file_output = { + "cal_pwr": cal_power, + "cal_values": cal_values.tolist(), } + with open(calibration_path, "w") as outfile: + json.dump(file_output, outfile) + #write corrections back to processing + + #readback from file is to circumvent a wierd formatting issue I can't figure out + + sleep(0.1) path = Path(self.config_directory, "calibration.json") - with open(path, "w") as input_file: - json.dump(cal_data, input_file) + with open(path, "r") as input_file: + cal_data = json.load(input_file) + self.cal_values = cal_data["cal_values"] + self.cal_power = cal_data["cal_pwr"] self.radio_queue.put(("cal_pwr", self.cal_power)) self.radio_queue.put(("cal_values", self.cal_values)) - # #disable calibration source and return + self.log_message("Calibration Done") - def start_recording(self, name): + def start_recording(self, name, file_dir): """Starts Recording Data Parameters @@ -575,14 +569,14 @@ def start_recording(self, name): if self.radio_save_task is None: if name is None: self.radio_save_task = RadioSaveRawTask( - self.radio_sample_frequency, self.save_dir, name + self.radio_sample_frequency, file_dir, name ) elif name.endswith(".rad"): name = None if name == "*.rad" else name self.radio_save_task = RadioSaveSpecRadTask( self.radio_sample_frequency, self.radio_num_bins, - self.save_dir, + file_dir, name, ) elif name.endswith(".fits"): @@ -590,12 +584,12 @@ def start_recording(self, name): self.radio_save_task = RadioSaveSpecFitsTask( self.radio_sample_frequency, self.radio_num_bins, - self.save_dir, + file_dir, name, ) else: self.radio_save_task = RadioSaveRawTask( - self.radio_sample_frequency, self.save_dir, name + self.radio_sample_frequency, file_dir, name ) self.radio_save_task.start() else: @@ -1060,8 +1054,7 @@ def srt_daemon_main(self): self.quit() elif command_name == "record": self.start_recording( - name=(None if len(command_parts) - <= 1 else command_parts[1]) + name=(None if len(command_parts) <= 1 else command_parts[1]), file_dir=self.save_dir ) elif command_name == "roff": self.stop_recording() diff --git a/srt/daemon/utilities/calibration_functions.py b/srt/daemon/utilities/calibration_functions.py new file mode 100644 index 00000000..97256ad7 --- /dev/null +++ b/srt/daemon/utilities/calibration_functions.py @@ -0,0 +1,72 @@ +"""calibration_functions.py + +dsheen 2024/09/18 +Calibration Mathhematics for new SRT calibration scheme + +reimplements basic cold sky cal implemented directly in gnuradio +and adds additional capabilities for more advanced telescopes. +""" + +import numpy as np +import numpy.polynomial.polynomial as poly +from astropy.io import fits + +def get_averaged_spectrum(fits_file): + """ + open fits file and average all included spectra together + """ + spectrum_file = fits.open(fits_file) + average_spectrum = np.zeros(len(spectrum_file[0].data),dtype=np.float64) + + num_spectra = len(spectrum_file) + for i in range(0,num_spectra): + spectrum=spectrum_file[i] + average_spectrum += spectrum.data + + average_spectrum /= num_spectra + + return average_spectrum + + +def basic_cold_sky_calibration_fit(cold_sky_reference_filepath, t_sys=300, t_cal=300, polynomial_order=20): + """ + very basic calibration for single point temperature reference measurement. + calculates a polynomial fit for the spectrum and appropriately normalizes it + """ + + average_cold_sky_spectrum = get_averaged_spectrum(cold_sky_reference_filepath) + relative_freq_values = np.linspace(-1, 1, len(average_cold_sky_spectrum)) + polynomial_fit = poly.Polynomial.fit(relative_freq_values, average_cold_sky_spectrum, polynomial_order,) + + smoothed_cold_sky_spectrum = polynomial_fit(relative_freq_values) + average_value = np.average(smoothed_cold_sky_spectrum) + normalized_gain_spectrum = smoothed_cold_sky_spectrum/average_value + average_gain_correction = average_value/(t_sys+t_cal) + + + return normalized_gain_spectrum, average_gain_correction + + +def additive_noise_calibration_fit(cold_sky_reference_filepath, calibrator_reference_filepath, t_sys=300, t_cal=300, polynomial_order=20): + + average_cold_sky_spectrum = get_averaged_spectrum(cold_sky_reference_filepath) + average_calibrator_plus_sky_spectrum = get_averaged_spectrum(calibrator_reference_filepath) + average_calibrator_spectrum = average_calibrator_plus_sky_spectrum - average_cold_sky_spectrum + + relative_freq_values = np.linspace(-1, 1, len(average_cold_sky_spectrum)) + polynomial_fit = poly.Polynomial.fit(relative_freq_values, average_calibrator_spectrum, polynomial_order,) + + smoothed_calibrator_spectrum = polynomial_fit(relative_freq_values) + average_value = np.average(smoothed_calibrator_spectrum) + normalized_gain_spectrum = smoothed_calibrator_spectrum/average_value + average_gain_correction = average_value/t_cal + + return normalized_gain_spectrum, average_gain_correction + + + + + + + + From ca5963934e5ead9a0d10915c1d0bcd38d12bea6e Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 17:59:37 -0400 Subject: [PATCH 38/79] . --- config/sky_coords.csv | 40 ++-------------------------------------- 1 file changed, 2 insertions(+), 38 deletions(-) diff --git a/config/sky_coords.csv b/config/sky_coords.csv index ccad55f8..7c7a7d5e 100644 --- a/config/sky_coords.csv +++ b/config/sky_coords.csv @@ -15,7 +15,7 @@ fk4,05 14 12,18 44 00,AC1 fk4,03 29 00,54 00 00,PULSAR fk4,08 30 00,-45 00 00,PS galactic,10,1,RC_CLOUD -galactic,0,0,G00 +galactic,00,0,G00 galactic,10,0,G10 galactic,20,0,G20 galactic,30,0,G30 @@ -50,40 +50,4 @@ galactic,310,0,G310 galactic,320,0,G320 galactic,330,0,G330 galactic,340,0,G340 -galactic,350,0,G350 -galactic,5,0,G05 -galactic,15,0,G15 -galactic,25,0,G25 -galactic,35,0,G35 -galactic,45,0,G45 -galactic,55,0,G55 -galactic,65,0,G65 -galactic,75,0,G75 -galactic,85,0,G85 -galactic,95,0,G95 -galactic,105,0,G105 -galactic,115,0,G115 -galactic,125,0,G125 -galactic,135,0,G135 -galactic,145,0,G145 -galactic,155,0,G155 -galactic,165,0,G165 -galactic,175,0,G175 -galactic,185,0,G185 -galactic,195,0,G195 -galactic,205,0,G205 -galactic,215,0,G215 -galactic,225,0,G225 -galactic,235,0,G235 -galactic,245,0,G245 -galactic,255,0,G255 -galactic,265,0,G265 -galactic,275,0,G275 -galactic,285,0,G285 -galactic,295,0,G295 -galactic,305,0,G305 -galactic,315,0,G315 -galactic,325,0,G325 -galactic,335,0,G335 -galactic,345,0,G345 -galactic,355,0,G355 +galactic,350,0,G350 \ No newline at end of file From b2c21d97c98ea588990d6d01d3bbe8151799f40e Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sat, 21 Sep 2024 22:32:25 +0000 Subject: [PATCH 39/79] added catch for exception in monitor.py objects import since that seems broken --- srt/daemon/daemon.py | 4 ++-- srt/dashboard/layouts/monitor_page.py | 19 ++++++++++++------- 2 files changed, 14 insertions(+), 9 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 98cad7f8..e810c90e 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -833,7 +833,7 @@ def update_rotor_status(self): ) and (time() - start_time) < 10: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() - print(past_rotor_location, self.rotor_location) + #print(past_rotor_location, self.rotor_location) if not self.rotor_location == past_rotor_location: g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord( self.rotor_location @@ -850,7 +850,7 @@ def update_rotor_status(self): else: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() - print(self.rotor_location) + #print(self.rotor_location) if not self.rotor_location == past_rotor_location: g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord( self.rotor_location diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 28138012..e9624ce0 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -45,15 +45,20 @@ from srt import config_loader -root_folder = Path(__file__).parent.parent.parent.parent +#root_folder = Path(__file__).parent.parent.parent.parent +#the above appears to be broken +root_folder = "$HOME/srt-py" - -def get_all_objects(config_file="config/sky_coords.csv",): - table = Table.read(Path(root_folder, config_file), format="ascii.csv") +def get_all_objects(coords_file="config/sky_coords.csv",): all_objects = ["Sun", "Moon"] - for index, row in enumerate(table): - name = row["name"] - all_objects.append(name) + try: + table = Table.read(Path(root_folder, coords_file), format="ascii.csv") + + for index, row in enumerate(table): + name = row["name"] + all_objects.append(name) + except: + table = all_objects #just to do something return all_objects From fab0b757ed8355eef6840beda8a551cae70297f2 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 18:50:32 -0400 Subject: [PATCH 40/79] minor tweak to monitor page but seems like something is very borked and idk quite what --- srt/dashboard/layouts/monitor_page.py | 38 +++++++++++++-------------- 1 file changed, 18 insertions(+), 20 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index e9624ce0..2db20cdd 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1586,24 +1586,24 @@ def record_click_func( return not is_open return is_open - @ app.callback( - Output("recording-alert", "is_open"), - [Input("record-btn-yes", "n_clicks"), - Input("btn-stop-record", "n_clicks")], - [], - ) - def record_alert_func(n_clicks_start, n_clicks_stop): - ctx = dash.callback_context - if not ctx.triggered: - return False - else: - if not n_clicks_start: - return False - if not n_clicks_stop: - return True - if n_clicks_start == n_clicks_stop: - return False - return True + #@ app.callback( + # Output("recording-alert", "is_open"), + # [Input("record-btn-yes", "n_clicks"), + # Input("btn-stop-record", "n_clicks")], + # [], + #) + #def record_alert_func(n_clicks_start, n_clicks_stop): + # ctx = dash.callback_context + # if not ctx.triggered: + # return False + # else: + # if not n_clicks_start: + # return False + # if not n_clicks_stop: + # return True + # if n_clicks_start == n_clicks_stop: + # return False + # return True @ app.callback( Output("cmd-file-modal", "is_open"), @@ -1685,7 +1685,6 @@ def cmd_button_pressed( n_clicks_calibrate, n_clicks_calon, n_clicks_caloff, - is_open ): ctx = dash.callback_context if not ctx.triggered: @@ -1696,7 +1695,6 @@ def cmd_button_pressed( command_thread.add_to_queue("stow") if button_id == "btn-stop-record": command_thread.add_to_queue("roff") - return not is_open elif button_id == "btn-quit": command_thread.add_to_queue("quit") elif button_id == "btn-calibrate": From cd5d6d4f4d630573ea9353ac8af6b5a1b8a15745 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 19:07:35 -0400 Subject: [PATCH 41/79] mod command_button_presed definition in monitor.py to hopefully work again --- srt/dashboard/layouts/monitor_page.py | 1 - 1 file changed, 1 deletion(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 2db20cdd..f4e27028 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1676,7 +1676,6 @@ def run_srt_daemon(configuration_dir, configuration_dict): Input("btn-calon", "n_clicks"), Input("btn-caloff", "n_clicks"), ], - [State("recording-alert", "is_open")] ) def cmd_button_pressed( n_clicks_stow, From cc19732fe7851dd90f0ebaa1175ab890cfce9d7d Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Sat, 21 Sep 2024 23:28:14 +0000 Subject: [PATCH 42/79] FINALLY! actually have everything working --- config/config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/config.yaml b/config/config.yaml index e565b0d7..a4ddb392 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -49,4 +49,4 @@ RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 200 +DASHBOARD_REFRESH_MS: 500 From 26a8c9a625508b2423a2a0011e765d6553ee7f30 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 19:34:36 -0400 Subject: [PATCH 43/79] Removed old bad interpolated N point graph and changed graphs order --- srt/dashboard/layouts/monitor_page.py | 134 ++++++++++++++++---------- 1 file changed, 85 insertions(+), 49 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index f4e27028..ba4eedbb 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -37,7 +37,6 @@ generate_spectrum_graph, generate_zoom_graph, generate_npoint_raw, - generate_npoint_interpolated, emptygraph, ) @@ -95,6 +94,7 @@ def generate_first_row(): ) + def generate_srt_azel(): """Generates AzEl Display @@ -134,10 +134,10 @@ def generate_npointlayout(): [dcc.Graph(id="npoint-graph-1")], className="pretty_container six columns", ), - html.Div( - [dcc.Graph(id="npoint-graph-2")], - className="pretty_container six columns", - ), + #html.Div( + # [dcc.Graph(id="npoint-graph-2")], + # className="pretty_container six columns", + # ), # html.Div( # [dcc.Graph(id="beamsswitch-graph")], # className="pretty_container six columns", @@ -152,6 +152,7 @@ def generate_npointlayout(): ] ) + def generate_srt_second_row(): """Generates N Point Display and zoomed in map @@ -209,6 +210,41 @@ def generate_second_row(): ), ) +def generate_npointlayout(): + """Generates N Point Display + + Returns + ------- + Div containing n point graph if srt + """ + return html.Div( + [ + html.Div( + [ + dcc.Store(id="npoint_info", storage_type="session"), + html.Div( + [dcc.Graph(id="npoint-graph-1")], + className="pretty_container six columns", + ), + #html.Div( + # [dcc.Graph(id="npoint-graph-2")], + # className="pretty_container six columns", + # ), + # html.Div( + # [dcc.Graph(id="beamsswitch-graph")], + # className="pretty_container six columns", + # ), + ], + className="flex-display", + style={ + "justify-content": "left", + "margin": "5px", + }, + ), + ] + ) + + def generate_third_row(): """Generates Third Row (AzEl Time) Display @@ -909,8 +945,8 @@ def generate_layout(software): layout = html.Div( [ generate_navbar(drop_down_buttons_vsrt), - dbc.Alert("Recording", color="danger", - id="recording-alert", is_open=False), + #dbc.Alert("Recording", color="danger", + # id="recording-alert", is_open=False), generate_first_row(), generate_second_row(), generate_third_row(), @@ -922,8 +958,8 @@ def generate_layout(software): layout = html.Div( [ generate_navbar(drop_down_buttons_srt), - dbc.Alert("Recording", color="danger", - id="recording-alert", is_open=False), + #dbc.Alert("Recording", color="danger", + # id="recording-alert", is_open=False), generate_first_row(), generate_srt_azel(), generate_srt_second_row(), @@ -1095,46 +1131,46 @@ def update_n_point_raw(ts, npdata): ofig = generate_npoint_raw(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) return ofig - @app.callback( - Output("npoint-graph-2", "figure"), - [Input("npoint_info", "modified_timestamp")], - [State("npoint_info", "data")], - ) - def update_n_point_interpolated(ts, npdata): - """Update the npoint track info - - Parameters - ---------- - ts : int - modified time stamp - npdata : dict - will hold N- point data. - - Returns - ------- - ofig : plotly.fig - Plotly figure - """ - - if ts is None: - raise PreventUpdate - if npdata is None: - return emptygraph("x", "y", "N-Point Scan") - - if npdata.get("scan_center", [1, 1])[0] == 0: - return emptygraph("x", "y", "N-Point Scan") - - az_a = [] - el_a = [] - for irot in npdata["rotor_loc"]: - az_a.append(irot[0]) - el_a.append(irot[1]) - mdiff = npdata["maxdiff"] - sc = npdata["scan_center"] - plist = npdata["pwr"] - sd = npdata["sides"] - ofig = generate_npoint_interpolated(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) - return ofig + # @app.callback( + # Output("npoint-graph-2", "figure"), + # [Input("npoint_info", "modified_timestamp")], + # [State("npoint_info", "data")], + # ) + # def update_n_point_interpolated(ts, npdata): + # """Update the npoint track info + + # Parameters + # ---------- + # ts : int + # modified time stamp + # npdata : dict + # will hold N- point data. + + # Returns + # ------- + # ofig : plotly.fig + # Plotly figure + # """ + + # if ts is None: + # raise PreventUpdate + # if npdata is None: + # return emptygraph("x", "y", "N-Point Scan") + + # if npdata.get("scan_center", [1, 1])[0] == 0: + # return emptygraph("x", "y", "N-Point Scan") + + # az_a = [] + # el_a = [] + # for irot in npdata["rotor_loc"]: + # az_a.append(irot[0]) + # el_a.append(irot[1]) + # mdiff = npdata["maxdiff"] + # sc = npdata["scan_center"] + # plist = npdata["pwr"] + # sd = npdata["sides"] + # ofig = generate_npoint_interpolated(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd) + # return ofig @app.callback( From d1ff9ae65ce192c594ba64a78f2f4f9da09ad0ae Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 19:45:38 -0400 Subject: [PATCH 44/79] swapped N point order in display --- srt/dashboard/layouts/monitor_page.py | 37 +-------------------------- 1 file changed, 1 insertion(+), 36 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index ba4eedbb..2a92792c 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -117,41 +117,6 @@ def generate_srt_azel(): ), ) -def generate_npointlayout(): - """Generates N Point Display - - Returns - ------- - Div: html.Div - containing n point graph if srt - """ - return html.Div( - [ - html.Div( - [ - dcc.Store(id="npoint_info", storage_type="session"), - html.Div( - [dcc.Graph(id="npoint-graph-1")], - className="pretty_container six columns", - ), - #html.Div( - # [dcc.Graph(id="npoint-graph-2")], - # className="pretty_container six columns", - # ), - # html.Div( - # [dcc.Graph(id="beamsswitch-graph")], - # className="pretty_container six columns", - # ), - ], - className="flex-display", - style={ - "justify-content": "left", - "margin": "5px", - }, - ), - ] - ) - def generate_srt_second_row(): """Generates N Point Display and zoomed in map @@ -167,7 +132,7 @@ def generate_srt_second_row(): [ dcc.Store(id="npoint_info", storage_type="session"), html.Div( - [dcc.Graph(id="npoint-graph")], + [dcc.Graph(id="npoint-graph-1")], className="pretty_container six columns", ), html.Div( From fd83ccb3026e32ec8ec538d69a1764de78790196 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Sat, 21 Sep 2024 21:12:28 -0400 Subject: [PATCH 45/79] make beam footpring in zoom plot round --- srt/dashboard/layouts/graphs.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index 38b4918c..ed4726f8 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -295,13 +295,13 @@ def generate_zoom_graph( ) ) fig.add_shape( - type="rect", + type="circle", xref="x", yref="y", - x0=current_location[0]-beam_width, - y0=current_location[1]-beam_width, - x1=current_location[0]+beam_width, - y1=current_location[1]+beam_width, + x0=current_location[0]-beam_width/2, + y0=current_location[1]-beam_width/2, + x1=current_location[0]+beam_width/2, + y1=current_location[1]+beam_width/2, fillcolor="lightgrey", layer="below", label=dict(text="Beamwidth", textposition="top center", From 6bfca458f9b6b3e89bd559b30019fb587e0a2048 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Sat, 21 Sep 2024 22:26:22 -0400 Subject: [PATCH 46/79] Corrected VLSR Calculation per Jorian --- srt/daemon/utilities/object_tracker.py | 35 ++++++++++++++++++++++---- 1 file changed, 30 insertions(+), 5 deletions(-) diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index c58c5b82..717048e0 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -4,7 +4,7 @@ """ from astropy.coordinates import SkyCoord, EarthLocation, get_sun, get_moon -from astropy.coordinates import ICRS, Galactic, FK4, CIRS, AltAz +from astropy.coordinates import ICRS, Galactic, FK4, CIRS, AltAz, LSR from astropy.utils.iers.iers import conf from astropy.table import Table from astropy.time import Time @@ -146,13 +146,36 @@ def calculate_vlsr(self, name, time, frame): """ if name == "Sun": tframe = get_sun(time).transform_to(frame) - vlsr = tframe.radial_velocity_correction(obstime=time) + v_bary = tframe.radial_velocity_correction(obstime=time) + # vlsr = tframe.transform_to(LSR()).radial_velocity + + sky_coord_radec = tframe.transform_to('icrs') + my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, + pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, + radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. + vlsr = my_observation.transform_to(LSR()).radial_velocity + elif name == "Moon": tframe = get_moon(time).transform_to(frame) - vlsr = tframe.radial_velocity_correction(obstime=time) + v_bary = tframe.radial_velocity_correction(obstime=time) + # vlsr = tframe.transform_to(LSR()).radial_velocity + + sky_coord_radec = tframe.transform_to('icrs') + my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, + pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, + radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. + vlsr = my_observation.transform_to(LSR()).radial_velocity + else: tframe = self.sky_coord_names[name].transform_to(frame) - vlsr = tframe.radial_velocity_correction(obstime=time) + v_bary = tframe.radial_velocity_correction(obstime=time) + # vlsr = self.sky_coord_names[name].transform_to(LSR()).radial_velocity + + sky_coord_radec = tframe.transform_to('icrs') + my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, + pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, + radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. + vlsr = my_observation.transform_to(LSR()).radial_velocity return vlsr.to(u.km / u.s).value @@ -183,7 +206,9 @@ def calculate_vlsr_azel(self, az_el, time=None): result = start_frame.transform_to(end_frame) sk1 = SkyCoord(result) f1 = AltAz(obstime=time, location=self.location) - vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) + #vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) + vbary = sk1.transform_to(f1).radial_velocity_correction(obstime=time) + vlsr = sk1.transform_to(LSR()).radial_velocity return vlsr.to(u.km/u.s).value From c28f33edea24bb271e8c4390a1b05931f0cd5631 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Sun, 22 Sep 2024 20:20:54 -0400 Subject: [PATCH 47/79] update calculate_vlsr_azel function with hopefuly now correct vlsr math --- srt/daemon/utilities/object_tracker.py | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 717048e0..92f86eb0 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -185,7 +185,7 @@ def calculate_vlsr_azel(self, az_el, time=None): Parameters ---------- az_el : (float, float) - Azimuth and Elevation + Azimuth and Elevation time : AstroPy Time Obj Time of Conversion @@ -197,7 +197,7 @@ def calculate_vlsr_azel(self, az_el, time=None): if time is None: time = Time.now() - + az, el = az_el start_frame = AltAz( obstime=time, location=self.location, alt=el * u.deg, az=az * u.deg @@ -205,10 +205,17 @@ def calculate_vlsr_azel(self, az_el, time=None): end_frame = Galactic() result = start_frame.transform_to(end_frame) sk1 = SkyCoord(result) - f1 = AltAz(obstime=time, location=self.location) + f1 = AltAz(obstime=time,location=self.location) #vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) - vbary = sk1.transform_to(f1).radial_velocity_correction(obstime=time) - vlsr = sk1.transform_to(LSR()).radial_velocity + v_bary = sk1.transform_to(f1).radial_velocity_correction(obstime=time) + + sky_coord_radec = sk1.transform_to('icrs') + my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, + pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, + radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. + vlsr = my_observation.transform_to(LSR()).radial_velocity + + # vlsr = sk1.transform_to(LSR()).radial_velocity return vlsr.to(u.km/u.s).value From cf3de5f44bd17520b1d62079719c3543eae585f1 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Mon, 23 Sep 2024 23:35:18 +0000 Subject: [PATCH 48/79] disabled azeltime graph for normal SRT code to make UI more responsive --- srt/daemon/daemon.py | 5 +++-- srt/dashboard/layouts/graphs.py | 12 ++++++++---- srt/dashboard/layouts/monitor_page.py | 2 +- 3 files changed, 12 insertions(+), 7 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index e810c90e..db86d513 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -93,6 +93,7 @@ def __init__(self, config_directory, config_dict): self.temp_sys = config_dict["TSYS"] self.temp_cal = config_dict["TCAL"] self.save_dir = config_dict["SAVE_DIRECTORY"] + self.dashboard_refresh_rate = config_dict["DASHBOARD_REFRESH_MS"]/1000.0 self.npoints = 5 #default size of grid for npoint scan self.radio_calibrator_state = False @@ -824,7 +825,7 @@ def update_rotor_status(self): ): self.rotor.set_azimuth_elevation( *current_rotor_cmd_location) - sleep(1) + sleep(0.1) start_time = time() while ( not azel_within_range( @@ -846,7 +847,7 @@ def update_rotor_status(self): ) self.radio_queue.put(("glat", g_lat)) self.radio_queue.put(("glon", g_lon)) - sleep(0.5) + sleep(0.1) else: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index ed4726f8..2a1623b9 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -276,8 +276,12 @@ def generate_zoom_graph( """ fig = go.Figure() - az_lower_display_lim = current_location[0]-beam_width*2 - az_upper_display_lim = current_location[0]+beam_width*2 + #correct for azel coordinates distortion on sky + #el_bw = beam_width + az_bw = beam_width/np.cos(current_location[1] * np.pi / 180.0) + + az_lower_display_lim = current_location[0]-az_bw*2 + az_upper_display_lim = current_location[0]+az_bw*2 el_lower_display_lim = current_location[1]-beam_width*2 el_upper_display_lim = current_location[1]+beam_width*2 @@ -298,9 +302,9 @@ def generate_zoom_graph( type="circle", xref="x", yref="y", - x0=current_location[0]-beam_width/2, + x0=current_location[0]-az_bw/2, y0=current_location[1]-beam_width/2, - x1=current_location[0]+beam_width/2, + x1=current_location[0]+az_bw/2, y1=current_location[1]+beam_width/2, fillcolor="lightgrey", layer="below", diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 2a92792c..260dd825 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -928,7 +928,7 @@ def generate_layout(software): generate_first_row(), generate_srt_azel(), generate_srt_second_row(), - generate_third_row(), + #generate_third_row(), generate_popups(software), html.Div(id="signal", style={"display": "none"}), ] From da91f190c75064c2a25f35e3d9f1dd9ad8f73111 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Mon, 23 Sep 2024 19:40:31 -0400 Subject: [PATCH 49/79] returned object tracker to base haystack code for now --- srt/daemon/utilities/object_tracker.py | 50 +++++--------------------- 1 file changed, 9 insertions(+), 41 deletions(-) diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 92f86eb0..f09947c5 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -126,7 +126,7 @@ def calculate_az_el(self, name, time, alt_az_frame): ) return alt_az.az.degree, alt_az.alt.degree - def calculate_vlsr(self, name, time, frame): + def calculate_vlsr(self, name, time, frame): """Calculates the velocity in the local standard of rest. Parameters @@ -146,36 +146,13 @@ def calculate_vlsr(self, name, time, frame): """ if name == "Sun": tframe = get_sun(time).transform_to(frame) - v_bary = tframe.radial_velocity_correction(obstime=time) - # vlsr = tframe.transform_to(LSR()).radial_velocity - - sky_coord_radec = tframe.transform_to('icrs') - my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, - pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, - radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. - vlsr = my_observation.transform_to(LSR()).radial_velocity - + vlsr = tframe.radial_velocity_correction(obstime=time) elif name == "Moon": tframe = get_moon(time).transform_to(frame) - v_bary = tframe.radial_velocity_correction(obstime=time) - # vlsr = tframe.transform_to(LSR()).radial_velocity - - sky_coord_radec = tframe.transform_to('icrs') - my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, - pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, - radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. - vlsr = my_observation.transform_to(LSR()).radial_velocity - + vlsr = tframe.radial_velocity_correction(obstime=time) else: tframe = self.sky_coord_names[name].transform_to(frame) - v_bary = tframe.radial_velocity_correction(obstime=time) - # vlsr = self.sky_coord_names[name].transform_to(LSR()).radial_velocity - - sky_coord_radec = tframe.transform_to('icrs') - my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, - pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, - radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. - vlsr = my_observation.transform_to(LSR()).radial_velocity + vlsr = tframe.radial_velocity_correction(obstime=time) return vlsr.to(u.km / u.s).value @@ -185,7 +162,7 @@ def calculate_vlsr_azel(self, az_el, time=None): Parameters ---------- az_el : (float, float) - Azimuth and Elevation + Azimuth and Elevation time : AstroPy Time Obj Time of Conversion @@ -197,7 +174,7 @@ def calculate_vlsr_azel(self, az_el, time=None): if time is None: time = Time.now() - + az, el = az_el start_frame = AltAz( obstime=time, location=self.location, alt=el * u.deg, az=az * u.deg @@ -205,20 +182,11 @@ def calculate_vlsr_azel(self, az_el, time=None): end_frame = Galactic() result = start_frame.transform_to(end_frame) sk1 = SkyCoord(result) - f1 = AltAz(obstime=time,location=self.location) - #vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) - v_bary = sk1.transform_to(f1).radial_velocity_correction(obstime=time) - - sky_coord_radec = sk1.transform_to('icrs') - my_observation = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, - pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, - radial_velocity=v_bary, distance = 1*u.pc) #distance does not matter. - vlsr = my_observation.transform_to(LSR()).radial_velocity - - # vlsr = sk1.transform_to(LSR()).radial_velocity + f1 = AltAz(obstime=time, location=self.location) + vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) return vlsr.to(u.km/u.s).value - + def convert_to_gal_coord(self, az_el, time=None): """Converts an AzEl Tuple into a Galactic Tuple from Location From 012fd7168bf7b8d5df32f5fc8092e6bdf3db9910 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 24 Sep 2024 00:20:32 +0000 Subject: [PATCH 50/79] changed beam marker in main azel plot to be oval stretched in azimuth appropriately for elevation. plus minor other code corrections --- config/config.yaml | 2 +- srt/daemon/daemon.py | 2 +- srt/daemon/utilities/object_tracker.py | 2 +- srt/dashboard/layouts/graphs.py | 35 ++++++++------------ srt/dashboard/messaging/raw_radio_fetcher.py | 2 +- 5 files changed, 18 insertions(+), 25 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index a4ddb392..a0c509e4 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -49,4 +49,4 @@ RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 500 +DASHBOARD_REFRESH_MS: 1000 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index db86d513..6ef9bbea 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -916,7 +916,7 @@ def update_status(self): "cal_state": self.radio_calibrator_state, } status_socket.send_json(status) - sleep(0.1) + sleep(0.2) def update_radio_settings(self): """Coordinates Sending XMLRPC Commands to the GNU Radio Script diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index f09947c5..a89da5a0 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -126,7 +126,7 @@ def calculate_az_el(self, name, time, alt_az_frame): ) return alt_az.az.degree, alt_az.alt.degree - def calculate_vlsr(self, name, time, frame): + def calculate_vlsr(self, name, time, frame): """Calculates the velocity in the local standard of rest. Parameters diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py index 2a1623b9..07ef4846 100644 --- a/srt/dashboard/layouts/graphs.py +++ b/srt/dashboard/layouts/graphs.py @@ -67,31 +67,24 @@ def generate_az_el_graph( ) ) - # Marker for visability, basicaslly beamwidth with azimuth stretched out for high elevation angles. + # Marker for visibility, basicaslly beamwidth with azimuth stretched out for high elevation angles. az_l = current_location[0] el_l = current_location[1] - el_u = el_l + .5*beam_width - el_d = el_l - .5*beam_width - - azu = .5*beam_width/np.cos(el_u * np.pi / 180.0) - azd = .5*beam_width/np.cos(el_d * np.pi / 180.0) - x_vec = [max(az_l-azd, 0), min(az_l-azu, 360), - max(az_l+azu, 0), min(az_l+azd, 360), max(az_l-azd, 0)] - y_vec = [max(el_d, 0), min(el_u, 90), min( - el_u, 90), min(el_d, 90), max(el_d, 0)] + az_bw = beam_width/np.cos(el_l * np.pi / 180.0) - fig.add_trace( - go.Scatter( - x=x_vec, - y=y_vec, - fill="toself", - fillcolor="rgba(147,112,219,0.1)", - text=["Visability"], - name='Visability', - mode="markers", - marker_color=["rgba(147,112,219, .8)" for _ in x_vec] - ) + fig.add_shape( + type="circle", + xref="x", + yref="y", + x0=az_l-az_bw/2, + y0=el_l-beam_width/2, + x1=az_l+az_bw/2, + y1=el_l+beam_width/2, + fillcolor="grey", + layer="below", + #label=dict(text="Beamwidth", textposition="top center", + # font=dict(color="White")) ) fig.add_trace( diff --git a/srt/dashboard/messaging/raw_radio_fetcher.py b/srt/dashboard/messaging/raw_radio_fetcher.py index 5fd43640..3883d071 100644 --- a/srt/dashboard/messaging/raw_radio_fetcher.py +++ b/srt/dashboard/messaging/raw_radio_fetcher.py @@ -51,7 +51,7 @@ def run(self): socket.subscribe("") while True: rec = socket.recv() - print(len(rec)) + #print(len(rec)) var = np.frombuffer(rec, dtype="complex64") new_history_index = self.history_index + len(var) self.history.put( From 1a4178448d2a18798919856aa1e4793198ba9ebc Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 24 Sep 2024 19:36:34 +0000 Subject: [PATCH 51/79] fixed broken timed command execution commands and added comments so it's clearer how they actually work. --- srt/daemon/daemon.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 6ef9bbea..7179cf19 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -1105,21 +1105,26 @@ def srt_daemon_main(self): elif command_name == "wait": sleep(float(command_parts[1])) # Wait Until Next Time H:M:S - elif command_name.split(":")[0] == "lst": - time_string = command_name.replace("LST:", "") + # command format is "wait_utc_hms hour:minute:second" with utc time + elif command_name == "wait_utc_hms": + time_string = command_parts[1] time_val = datetime.strptime(time_string, "%H:%M:%S") while time_val < datetime.utcfromtimestamp(time()): time_val += timedelta(days=1) time_delta = ( time_val - datetime.utcfromtimestamp(time()) ).total_seconds() + self.log_message(f'sleeping for {time_delta} seconds') sleep(time_delta) - elif len(command_name.split(":")) == 5: # Wait Until Y:D:H:M:S + # Wait until next time Y:D:H:M:S + # command format is "wait_utc_ydhms year:day:hour:minute:second" with utc time + elif command_name == "wait_utc_ydhms": time_val = datetime.strptime( - command_name, "%Y:%j:%H:%M:%S") + command_parts[1], "%Y:%j:%H:%M:%S") time_delta = ( time_val - datetime.utcfromtimestamp(time()) ).total_seconds() + self.log_message(f'sleeping for {time_delta} seconds') sleep(time_delta) else: self.log_message(f"Command Not Identified '{command}'") From ba334faea49e433cba3b6616a0abbd7978863fa0 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 24 Sep 2024 21:52:53 +0000 Subject: [PATCH 52/79] made the thing just take normal iso formatted times --- srt/daemon/daemon.py | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 7179cf19..9a86bea0 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -1116,16 +1116,19 @@ def srt_daemon_main(self): ).total_seconds() self.log_message(f'sleeping for {time_delta} seconds') sleep(time_delta) - # Wait until next time Y:D:H:M:S - # command format is "wait_utc_ydhms year:day:hour:minute:second" with utc time - elif command_name == "wait_utc_ydhms": - time_val = datetime.strptime( - command_parts[1], "%Y:%j:%H:%M:%S") + # Wait until next iso time + # command format is "wait_utc_iso %Y-%m-%dT%H:%M:%S.%f%z" with utc time + elif command_name == "wait_utc_iso": + time_val = datetime.fromisoformat( + command_parts[1]) time_delta = ( time_val - datetime.utcfromtimestamp(time()) ).total_seconds() - self.log_message(f'sleeping for {time_delta} seconds') - sleep(time_delta) + if time_delta > 0: + self.log_message(f'sleeping for {time_delta} seconds') + sleep(time_delta) + else: + self.log_message('target command time past. skipping wait') else: self.log_message(f"Command Not Identified '{command}'") self.command_queue.task_done() From 24a1389190278866c79770b0a90755f1f773ceb5 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 1 Oct 2024 16:55:13 -0400 Subject: [PATCH 53/79] overhaul of object_tracker.py code to have only one vlsr calculation function, plus adding framework for passing sky coords to daemon. --- srt/daemon/daemon.py | 41 ++++- srt/daemon/utilities/object_tracker.py | 203 +++++++++++++++---------- 2 files changed, 158 insertions(+), 86 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 9a86bea0..5a859613 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -29,6 +29,14 @@ from .utilities.functions import azel_within_range, get_spectrum from .utilities.calibration_functions import basic_cold_sky_calibration_fit, additive_noise_calibration_fit +#pull astropy things into the daemon too for now so we can create skycoord objects here more easily + +from astropy.coordinates import SkyCoord, EarthLocation, get_sun, get_moon +from astropy.coordinates import ICRS, Galactic, FK4, CIRS, AltAz, LSR +from astropy.utils.iers.iers import conf +from astropy.table import Table +from astropy.time import Time +import astropy.units as u class SmallRadioTelescopeDaemon: """ @@ -318,15 +326,21 @@ def point_at_azel(self, az, el): ------- None """ - # cur_vlsr = self.ephemeris_tracker.calculate_vlsr_azel((az,el)) - # self.radio_queue.put(("vlsr",cur_vlsr)) - # self.current_vlsr = cur_vlsr + + #define a skycoord object with az el position info + + obstime = Time.now() + + azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=el * u.deg, az=az * u.deg) + sky_coord = SkyCoord(azel_frame) + + self.ephemeris_cmd_location = None self.rotor_offsets = (0.0, 0.0) # Send az and el angles to sources track for the radio self.radio_queue.put(("soutrack", f"azel_{az}_{el}")) # Send vlsr to radio queue - cur_vlsr = self.ephemeris_tracker.calculate_vlsr_azel((az, el)) + cur_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord, obstime) self.current_vlsr = cur_vlsr self.radio_queue.put(("vlsr", float(cur_vlsr))) @@ -356,10 +370,15 @@ def point_at_galactic(self, l_pos, b_pos, duration): Returns ------- None - """ + """ + + #define a skycoord object with galactic coord info + + sky_coord = SkyCoord(l_pos, b_pos, frame='galactic', unit=u.deg, location=EphemerisTracker.location) if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): #rotor is smart enough to directly handle the command + self.log_message("direct ra dec coordinate commands not yet supported for your rotor") else: #rotor needs command converted to az-el @@ -382,6 +401,10 @@ def point_at_radec(self, ra_pos, dec_pos, duration): ------- None """ + + #define a skycoord object with galactic coord info + + sky_coord = SkyCoord(ra_pos, dec_pos, frame='icrs', unit=u.deg, location=EphemerisTracker.location) if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): #rotor is smart enough to directly handle the command @@ -784,7 +807,7 @@ def update_ephemeris_location(self): self.ephemeris_locations = ( self.ephemeris_tracker.get_all_azimuth_elevation() ) - self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() + self.ephemeris_vlsr = self.c.get_all_vlsr() self.ephemeris_time_locs = ( self.ephemeris_tracker.get_all_azel_time() ) @@ -806,6 +829,12 @@ def update_ephemeris_location(self): f"Object {self.ephemeris_cmd_location} moved out of motor bounds" ) self.ephemeris_cmd_location = None + else: #compute vlsr for where we're actually pointed + obstime = Time.now() + azel_frame = AltAz(obstime=obstime, location=EphemerisTracker.location, alt=el * u.deg, az=az * u.deg) + sky_coord = SkyCoord(azel_frame) + self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) + self.radio_queue.put(("vlsr", float(self.current_vlsr))) sleep(1) def update_rotor_status(self): diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index a89da5a0..69d9d4fe 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -3,7 +3,7 @@ Module for Tracking and Caching the Azimuth-Elevation Coords of Celestial Objects """ -from astropy.coordinates import SkyCoord, EarthLocation, get_sun, get_moon +from astropy.coordinates import SkyCoord, EarthLocation, get_body #get_sun, get_moon from astropy.coordinates import ICRS, Galactic, FK4, CIRS, AltAz, LSR from astropy.utils.iers.iers import conf from astropy.table import Table @@ -60,6 +60,7 @@ def __init__( sky_coords_ra = np.zeros(len(table)) sky_coords_dec = np.zeros(len(table)) + for index, row in enumerate(table): coordinate_system = row["coordinate_system"] coordinate_a = row["coordinate_a"] @@ -78,14 +79,18 @@ def __init__( sky_coords_dec[index] = sky_coord_transformed.dec.degree self.sky_coord_names[name] = index - self.sky_coords = SkyCoord( - ra=sky_coords_ra * u.deg, dec=sky_coords_dec * u.deg, frame=CIRS - ) self.location = EarthLocation.from_geodetic( lat=observer_lat * u.deg, lon=observer_lon * u.deg, height=observer_elevation * u.m, ) + + self.sky_coords = SkyCoord( + ra=sky_coords_ra * u.deg, dec=sky_coords_dec * u.deg, frame=CIRS, location=self.location + ) + + self.bodies = ["Sun, Moon"] #list bodies we want to track so other functions can grab these (really should pull in from config file) + self.latest_time = None self.refresh_time = refresh_time * u.second @@ -99,6 +104,7 @@ def __init__( # self.update_azeltime() conf.auto_download = auto_download + def calculate_az_el(self, name, time, alt_az_frame): """Calculates Azimuth and Elevation of the Specified Object at the Specified Time @@ -116,76 +122,108 @@ def calculate_az_el(self, name, time, alt_az_frame): (float, float) (az, el) Tuple """ - if name == "Sun": - alt_az = get_sun(time).transform_to(alt_az_frame) - elif name == "Moon": - alt_az = get_moon(time, self.location).transform_to(alt_az_frame) + if (name == "Sun") or (name =="Moon"): + alt_az = get_body(time=time, body=name,location=self.location).transform_to(alt_az_frame) else: alt_az = self.sky_coords[self.sky_coord_names[name]].transform_to( alt_az_frame ) return alt_az.az.degree, alt_az.alt.degree - def calculate_vlsr(self, name, time, frame): - """Calculates the velocity in the local standard of rest. - Parameters - ---------- - name : str - Name of the Object being Tracked - time : Time - Current Time (only necessary for Sun/Moon Ephemeris) - alt_az_frame : AltAz - AltAz Frame Object + def calculate_vlsr(self, sky_coord, time): - Returns - ------- - float - vlsr in km/s. """ - if name == "Sun": - tframe = get_sun(time).transform_to(frame) - vlsr = tframe.radial_velocity_correction(obstime=time) - elif name == "Moon": - tframe = get_moon(time).transform_to(frame) - vlsr = tframe.radial_velocity_correction(obstime=time) - else: - tframe = self.sky_coord_names[name].transform_to(frame) - vlsr = tframe.radial_velocity_correction(obstime=time) - - return vlsr.to(u.km / u.s).value - - def calculate_vlsr_azel(self, az_el, time=None): - """Takes an AzEl tuple and derives the vlsr from Location + Calculates observer velocity correction in the local standard of rest + (e.g. relative to galactic center) along telescope line of sight. + Note we do not actuially care about the details of the object and are not attempting to + correct for target motion. We only care about where we are pointing. Parameters ---------- - az_el : (float, float) - Azimuth and Elevation - time : AstroPy Time Obj - Time of Conversion - - Returns - ------- - float - vlsr in km/s. + sky_coord : SkyCoord + Sky cordinate object + note: must contain location attribute + time : Time + Time for conversion """ - - if time is None: - time = Time.now() - - az, el = az_el - start_frame = AltAz( - obstime=time, location=self.location, alt=el * u.deg, az=az * u.deg - ) - end_frame = Galactic() - result = start_frame.transform_to(end_frame) - sk1 = SkyCoord(result) - f1 = AltAz(obstime=time, location=self.location) - vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) - - return vlsr.to(u.km/u.s).value + + #cast anything into icrs to make life easy (note this means AltAz frames must contain a time) + sky_coord_radec = sky_coord.transform_to('icrs') + + #barycentric correction + v_bary = sky_coord_radec.radial_velocity_correction(obstime=time) + + sky_coord_no_vel = ICRS(ra=sky_coord_radec.ra.deg*u.deg, dec=sky_coord_radec.dec.deg*u.deg, + pm_ra_cosdec=0*u.mas/u.yr, pm_dec=0*u.mas/u.yr, + radial_velocity=0*u.km/u.yr, distance = 10*u.pc) + #solar motion wrt galactic center + v_sun = sky_coord_no_vel.transform_to(LSR()).radial_velocity + + return (v_bary+v_sun).to(u.km/u.s) + + + # def calculate_object_vlsr(self, name, time, frame): + # """Calculates the velocity in the local standard of rest. + + # Parameters + # ---------- + # name : str + # Name of the Object being Tracked + # time : Time + # Current Time (only necessary for Sun/Moon Ephemeris) + # alt_az_frame : AltAz + # AltAz Frame Object + + + # Returns + # ------- + # float + # vlsr in km/s. + # """ + # if name == "Sun": + # tframe = get_sun(time).transform_to(frame) + # vlsr = tframe.radial_velocity_correction(obstime=time) + # elif name == "Moon": + # tframe = get_moon(time).transform_to(frame) + # vlsr = tframe.radial_velocity_correction(obstime=time) + # else: + # tframe = self.sky_coord_names[name].transform_to(frame) + # vlsr = tframe.radial_velocity_correction(obstime=time) + + # return vlsr.to(u.km / u.s).value + + # def calculate_vlsr_azel(self, az_el, time=None): + # """Takes an AzEl tuple and derives the vlsr from Location + + # Parameters + # ---------- + # az_el : (float, float) + # Azimuth and Elevation + # time : AstroPy Time Obj + # Time of Conversion + + # Returns + # ------- + # float + # vlsr in km/s. + # """ + + # if time is None: + # time = Time.now() + + # az, el = az_el + # start_frame = AltAz( + # obstime=time, location=self.location, alt=el * u.deg, az=az * u.deg + # ) + # end_frame = Galactic() + # result = start_frame.transform_to(end_frame) + # sk1 = SkyCoord(result) + # f1 = AltAz(obstime=time, location=self.location) + # vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) + + # return vlsr.to(u.km/u.s).value def convert_to_gal_coord(self, az_el, time=None): """Converts an AzEl Tuple into a Galactic Tuple from Location @@ -221,26 +259,31 @@ def update_all_az_el(self): ------- None """ - if ( - self.latest_time is not None - and Time.now() < self.latest_time + self.refresh_time - ): + if (self.latest_time is not None + and Time.now() < self.latest_time + self.refresh_time): return + time = Time.now() frame = AltAz(obstime=time, location=self.location) transformed = self.sky_coords.transform_to(frame) + for name in self.sky_coord_names: index = self.sky_coord_names[name] self.az_el_dict[name] = ( transformed.az[index].degree, transformed.alt[index].degree, ) - vlsr = transformed[index].radial_velocity_correction(obstime=time) + vlsr = calculate_vlsr(transformed[index], time) self.vlsr_dict[name] = vlsr.to(u.km / u.s).value - self.az_el_dict["Sun"] = self.calculate_az_el("Sun", time, frame) - self.vlsr_dict["Sun"] = self.calculate_vlsr("Sun", time, frame) - self.az_el_dict["Moon"] = self.calculate_az_el("Moon", time, frame) - self.vlsr_dict["Moon"] = self.calculate_vlsr("Moon", time, frame) + + #deal with annoying things that move against the sky + + for body in self.bodies: + body_coords = get_body(time=time, body=body,location=self.location).transform_to(frame) + self.az_el_dict[body] = body_coords.az.degree, body_coords.alt.degree + self.vlsr_dict[body] = calculate_vlsr(body_coords, time) + + #and prepredict things (do we actually need this?) for time_passed in range(0, 61, 5): @@ -254,10 +297,10 @@ def update_all_az_el(self): transformed.az[index].degree, transformed.alt[index].degree, ) - self.time_interval_dict[time_passed]["Sun"] = self.calculate_az_el( - "Sun", time, frame) - self.time_interval_dict[time_passed]["Moon"] = self.calculate_az_el( - "Moon", time, frame) + + for body in self.bodies: + body_coords = get_body(time=time, body=body,location=self.location).transform_to(frame) + self.time_interval_dict[time_passed][body] = body_coords.az.degree, body_coords.alt.degree self.latest_time = time @@ -305,14 +348,14 @@ def get_azimuth_elevation(self, name, time_offset): def get_all_vlsr(self): return self.vlsr_dict - def get_vlsr(self, name, time_offset=0): + # def get_vlsr(self, name, time_offset=0): #not used - if time_offset == 0: - return self.get_all_vlsr()[name] - else: - time = Time.now() + time_offset - frame = AltAz(obstime=time, location=self.location) - return self.calculate_vlsr(name, time, frame) + # if time_offset == 0: + # return self.get_all_vlsr()[name] + # else: + # time = Time.now() + time_offset + # frame = AltAz(obstime=time, location=self.location) + # return self.calculate_object_vlsr(name, time, frame) def inital_azeltime(self): new_dict = {} From e51857df78e0e17e08c3bb37ce9d4cd2ee84f233 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 1 Oct 2024 17:04:05 -0400 Subject: [PATCH 54/79] commented out multiple apparently unused azel calculations in object_tracker.py --- srt/daemon/utilities/object_tracker.py | 40 +++++++++++++------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 69d9d4fe..94526ad3 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -323,27 +323,27 @@ def get_all_azel_time(self): # return return self.time_interval_dict - def get_azimuth_elevation(self, name, time_offset): - """Returns Individual Object AzEl at Specified Time Offset + # def get_azimuth_elevation(self, name, time_offset): + # """Returns Individual Object AzEl at Specified Time Offset - Parameters - ---------- - name : str - Object Name - time_offset : Time - Any Offset from the Current Time - Returns - ------- - (float, float) - (az, el) Tuple - """ - if time_offset == 0: - return self.get_all_azimuth_elevation()[name] - else: - time = Time.now() + time_offset - return self.calculate_az_el( - name, time, AltAz(obstime=time, location=self.location) - ) + # Parameters + # ---------- + # name : str + # Object Name + # time_offset : Time + # Any Offset from the Current Time + # Returns + # ------- + # (float, float) + # (az, el) Tuple + # """ + # if time_offset == 0: + # return self.get_all_azimuth_elevation()[name] + # else: + # time = Time.now() + time_offset + # return self.calculate_az_el( + # name, time, AltAz(obstime=time, location=self.location) + # ) def get_all_vlsr(self): return self.vlsr_dict From decbdd448a9ec4a74d4878529fa0301810c9fd38 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 1 Oct 2024 21:49:16 +0000 Subject: [PATCH 55/79] mostly working modulo type issue in status passing --- srt/daemon/daemon.py | 10 +++++----- srt/daemon/utilities/object_tracker.py | 10 +++++----- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 5a859613..f71f59e7 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -374,7 +374,7 @@ def point_at_galactic(self, l_pos, b_pos, duration): #define a skycoord object with galactic coord info - sky_coord = SkyCoord(l_pos, b_pos, frame='galactic', unit=u.deg, location=EphemerisTracker.location) + sky_coord = SkyCoord(l_pos, b_pos, frame='galactic', unit=u.deg, location=self.ephemeris_tracker.location) if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): #rotor is smart enough to directly handle the command @@ -404,7 +404,7 @@ def point_at_radec(self, ra_pos, dec_pos, duration): #define a skycoord object with galactic coord info - sky_coord = SkyCoord(ra_pos, dec_pos, frame='icrs', unit=u.deg, location=EphemerisTracker.location) + sky_coord = SkyCoord(ra_pos, dec_pos, frame='icrs', unit=u.deg, location=self.ephemeris_tracker.location) if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): #rotor is smart enough to directly handle the command @@ -807,7 +807,7 @@ def update_ephemeris_location(self): self.ephemeris_locations = ( self.ephemeris_tracker.get_all_azimuth_elevation() ) - self.ephemeris_vlsr = self.c.get_all_vlsr() + self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() self.ephemeris_time_locs = ( self.ephemeris_tracker.get_all_azel_time() ) @@ -831,10 +831,10 @@ def update_ephemeris_location(self): self.ephemeris_cmd_location = None else: #compute vlsr for where we're actually pointed obstime = Time.now() - azel_frame = AltAz(obstime=obstime, location=EphemerisTracker.location, alt=el * u.deg, az=az * u.deg) + azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) sky_coord = SkyCoord(azel_frame) self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) - self.radio_queue.put(("vlsr", float(self.current_vlsr))) + self.radio_queue.put(("vlsr", float(self.current_vlsr.to(u.km/u.s).value))) sleep(1) def update_rotor_status(self): diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 94526ad3..5d0063ea 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -89,7 +89,7 @@ def __init__( ra=sky_coords_ra * u.deg, dec=sky_coords_dec * u.deg, frame=CIRS, location=self.location ) - self.bodies = ["Sun, Moon"] #list bodies we want to track so other functions can grab these (really should pull in from config file) + self.bodies = ["Sun", "Moon"] #list bodies we want to track so other functions can grab these (really should pull in from config file) self.latest_time = None self.refresh_time = refresh_time * u.second @@ -273,15 +273,15 @@ def update_all_az_el(self): transformed.az[index].degree, transformed.alt[index].degree, ) - vlsr = calculate_vlsr(transformed[index], time) + vlsr = self.calculate_vlsr(transformed[index], time) self.vlsr_dict[name] = vlsr.to(u.km / u.s).value #deal with annoying things that move against the sky for body in self.bodies: body_coords = get_body(time=time, body=body,location=self.location).transform_to(frame) - self.az_el_dict[body] = body_coords.az.degree, body_coords.alt.degree - self.vlsr_dict[body] = calculate_vlsr(body_coords, time) + self.az_el_dict[body] = (body_coords.az.degree, body_coords.alt.degree) + self.vlsr_dict[body] = self.calculate_vlsr(body_coords, time).to(u.km/u.s).value #and prepredict things (do we actually need this?) @@ -300,7 +300,7 @@ def update_all_az_el(self): for body in self.bodies: body_coords = get_body(time=time, body=body,location=self.location).transform_to(frame) - self.time_interval_dict[time_passed][body] = body_coords.az.degree, body_coords.alt.degree + self.time_interval_dict[time_passed][body] = (body_coords.az.degree, body_coords.alt.degree) self.latest_time = time From e72411c3f9a3cf9ce59f1f3d8234dfd762adc4e3 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 1 Oct 2024 17:52:41 -0400 Subject: [PATCH 56/79] Update object_tracker.py --- srt/daemon/utilities/object_tracker.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 5d0063ea..71ded6a0 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -161,7 +161,7 @@ def calculate_vlsr(self, sky_coord, time): #solar motion wrt galactic center v_sun = sky_coord_no_vel.transform_to(LSR()).radial_velocity - return (v_bary+v_sun).to(u.km/u.s) + return (v_bary+v_sun).to(u.km/u.s).value # def calculate_object_vlsr(self, name, time, frame): @@ -274,14 +274,14 @@ def update_all_az_el(self): transformed.alt[index].degree, ) vlsr = self.calculate_vlsr(transformed[index], time) - self.vlsr_dict[name] = vlsr.to(u.km / u.s).value + self.vlsr_dict[name] = vlsr #deal with annoying things that move against the sky for body in self.bodies: body_coords = get_body(time=time, body=body,location=self.location).transform_to(frame) self.az_el_dict[body] = (body_coords.az.degree, body_coords.alt.degree) - self.vlsr_dict[body] = self.calculate_vlsr(body_coords, time).to(u.km/u.s).value + self.vlsr_dict[body] = self.calculate_vlsr(body_coords, time) #and prepredict things (do we actually need this?) From 798d44855d24cf40222ee01a53abde95db82e232 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 1 Oct 2024 17:54:06 -0400 Subject: [PATCH 57/79] Update daemon.py --- srt/daemon/daemon.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index f71f59e7..fc4cc643 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -834,7 +834,7 @@ def update_ephemeris_location(self): azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) sky_coord = SkyCoord(azel_frame) self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) - self.radio_queue.put(("vlsr", float(self.current_vlsr.to(u.km/u.s).value))) + self.radio_queue.put(("vlsr", float(self.current_vlsr))) sleep(1) def update_rotor_status(self): From fb7dcc5a84db70e64cd39930bc10ae918cf935ab Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 1 Oct 2024 19:06:57 -0400 Subject: [PATCH 58/79] further reduced unnecessary calculations of VLSR and simplified calls within code to depend only on celestial coordinate updates --- srt/daemon/daemon.py | 109 ++++++++++++------------- srt/daemon/utilities/object_tracker.py | 73 ++--------------- 2 files changed, 60 insertions(+), 122 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index fc4cc643..739e4a0f 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -131,7 +131,6 @@ def __init__(self, config_directory, config_dict): Path(config_directory, "sky_coords.csv").absolute()), ) self.ephemeris_locations = self.ephemeris_tracker.get_all_azimuth_elevation() - self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() self.ephemeris_time_locs = self.ephemeris_tracker.get_all_azel_time() self.current_vlsr = 0.0 self.ephemeris_cmd_location = None @@ -198,15 +197,18 @@ def n_point_scan(self, object_id, grid_size=5): """ self.ephemeris_cmd_location = None self.radio_queue.put(("soutrack", object_id)) + + scan_center = self.ephemeris_locations[object_id] + # Send vlsr to radio queue - cur_vlsr = self.ephemeris_vlsr[object_id] - self.radio_queue.put(("vlsr", float(cur_vlsr))) - self.current_vlsr = cur_vlsr + #cur_vlsr = self.ephemeris_vlsr[object_id] + #self.radio_queue.put(("vlsr", float(self.current_vlsr))) + #self.current_vlsr = cur_vlsr N_pnt_default = grid_size**2 rotor_loc = [] pwr_list = [] # - scan_center = self.ephemeris_locations[object_id] + np_sides = [grid_size, grid_size] for scan in range(N_pnt_default): scan_center = self.ephemeris_locations[object_id] #recompute target position for every iteration @@ -255,10 +257,7 @@ def beam_switch(self, object_id): """ self.ephemeris_cmd_location = None self.radio_queue.put(("soutrack", object_id)) - # Send vlsr to radio queue - cur_vlsr = self.ephemeris_vlsr[object_id] - self.radio_queue.put(("vlsr", float(cur_vlsr))) - self.current_vlsr = cur_vlsr + new_rotor_destination = self.ephemeris_locations[object_id] rotor_loc = [] pwr_list = [] @@ -283,7 +282,6 @@ def beam_switch(self, object_id): self.ephemeris_cmd_location = object_id self.beam_switch_data = [rotor_loc, pwr_list] - def point_at_object(self, object_id): """Points Antenna Directly at Object, and Sets Up Tracking to Follow it Parameters @@ -297,10 +295,7 @@ def point_at_object(self, object_id): """ self.rotor_offsets = (0.0, 0.0) self.radio_queue.put(("soutrack", object_id)) - # Send vlsr to radio queue - cur_vlsr = self.ephemeris_vlsr[object_id] - self.radio_queue.put(("vlsr", float(cur_vlsr))) - self.current_vlsr = cur_vlsr + new_rotor_cmd_location = self.ephemeris_locations[object_id] if self.rotor.angles_within_bounds(*new_rotor_cmd_location): self.ephemeris_cmd_location = object_id @@ -329,20 +324,16 @@ def point_at_azel(self, az, el): #define a skycoord object with az el position info - obstime = Time.now() + #obstime = Time.now() - azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=el * u.deg, az=az * u.deg) - sky_coord = SkyCoord(azel_frame) + #azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=el * u.deg, az=az * u.deg) + #sky_coord = SkyCoord(azel_frame) self.ephemeris_cmd_location = None self.rotor_offsets = (0.0, 0.0) # Send az and el angles to sources track for the radio self.radio_queue.put(("soutrack", f"azel_{az}_{el}")) - # Send vlsr to radio queue - cur_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord, obstime) - self.current_vlsr = cur_vlsr - self.radio_queue.put(("vlsr", float(cur_vlsr))) new_rotor_destination = (az, el) new_rotor_cmd_location = new_rotor_destination @@ -804,10 +795,13 @@ def update_ephemeris_location(self): if last_updated_time is None or time() - last_updated_time > 10: last_updated_time = time() self.ephemeris_tracker.update_all_az_el() - self.ephemeris_locations = ( - self.ephemeris_tracker.get_all_azimuth_elevation() - ) - self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() + self.ephemeris_locations = ( + self.ephemeris_tracker.get_all_azimuth_elevation() + ) + #only update vlsr when we care and only at cadence we update celestial coordinates + #do this in rotor update loop, not here + #self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() + self.ephemeris_time_locs = ( self.ephemeris_tracker.get_all_azel_time() ) @@ -815,7 +809,7 @@ def update_ephemeris_location(self): new_rotor_destination = self.ephemeris_locations[ self.ephemeris_cmd_location ] - self.current_vlsr = self.ephemeris_vlsr[self.ephemeris_cmd_location] + #self.current_vlsr = self.ephemeris_vlsr[self.ephemeris_cmd_location] new_rotor_cmd_location = tuple( map(add, new_rotor_destination, self.rotor_offsets) ) @@ -829,12 +823,7 @@ def update_ephemeris_location(self): f"Object {self.ephemeris_cmd_location} moved out of motor bounds" ) self.ephemeris_cmd_location = None - else: #compute vlsr for where we're actually pointed - obstime = Time.now() - azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) - sky_coord = SkyCoord(azel_frame) - self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) - self.radio_queue.put(("vlsr", float(self.current_vlsr))) + sleep(1) def update_rotor_status(self): @@ -850,8 +839,8 @@ def update_rotor_status(self): try: current_rotor_cmd_location = self.rotor_cmd_location if not azel_within_range( - self.rotor_location, current_rotor_cmd_location - ): + self.rotor_location, current_rotor_cmd_location): + self.rotor.set_azimuth_elevation( *current_rotor_cmd_location) sleep(0.1) @@ -865,36 +854,46 @@ def update_rotor_status(self): self.rotor_location = self.rotor.get_azimuth_elevation() #print(past_rotor_location, self.rotor_location) if not self.rotor_location == past_rotor_location: - g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord( - self.rotor_location - ) - self.radio_queue.put( - ("motor_az", float(self.rotor_location[0])) - ) - self.radio_queue.put( - ("motor_el", float(self.rotor_location[1])) - ) + + obstime = Time.now() + + g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord(self.rotor_location) + self.radio_queue.put(("motor_az", float(self.rotor_location[0]))) + self.radio_queue.put(("motor_el", float(self.rotor_location[1]))) self.radio_queue.put(("glat", g_lat)) self.radio_queue.put(("glon", g_lon)) + + #compute vlsr for where we're actually pointed. we don't really care if it's theoretically different for the target object + + azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) + sky_coord = SkyCoord(azel_frame) + self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) + self.radio_queue.put(("vlsr", float(self.current_vlsr))) + sleep(0.1) else: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() #print(self.rotor_location) - if not self.rotor_location == past_rotor_location: - g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord( - self.rotor_location - ) - self.radio_queue.put( - ("motor_az", float(self.rotor_location[0])) - ) - self.radio_queue.put( - ("motor_el", float(self.rotor_location[1])) - ) - self.radio_queue.put(("glat", g_lat)) - self.radio_queue.put(("glon", g_lon)) + #if not self.rotor_location == past_rotor_location: #we should not do this check, still want to update galactic lat and lon at reasonable cadence + + obstime = Time.now() + + g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord(self.rotor_location) + self.radio_queue.put(("motor_az", float(self.rotor_location[0]))) + self.radio_queue.put(("motor_el", float(self.rotor_location[1]))) + self.radio_queue.put(("glat", g_lat)) + self.radio_queue.put(("glon", g_lon)) + + #compute vlsr for where we're actually pointed. we don't really care if it's theoretically different for the target object + + azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) + sky_coord = SkyCoord(azel_frame) + self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) + self.radio_queue.put(("vlsr", float(self.current_vlsr))) sleep(1) + except AssertionError as e: self.log_message(str(e)) except ValueError as e: diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 71ded6a0..487f2015 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -95,7 +95,7 @@ def __init__( self.refresh_time = refresh_time * u.second self.az_el_dict = {} - self.vlsr_dict = {} + # self.vlsr_dict = {} # self.time_interval_dict = {} self.time_interval_dict = self.inital_azeltime() @@ -163,67 +163,6 @@ def calculate_vlsr(self, sky_coord, time): return (v_bary+v_sun).to(u.km/u.s).value - - # def calculate_object_vlsr(self, name, time, frame): - # """Calculates the velocity in the local standard of rest. - - # Parameters - # ---------- - # name : str - # Name of the Object being Tracked - # time : Time - # Current Time (only necessary for Sun/Moon Ephemeris) - # alt_az_frame : AltAz - # AltAz Frame Object - - - # Returns - # ------- - # float - # vlsr in km/s. - # """ - # if name == "Sun": - # tframe = get_sun(time).transform_to(frame) - # vlsr = tframe.radial_velocity_correction(obstime=time) - # elif name == "Moon": - # tframe = get_moon(time).transform_to(frame) - # vlsr = tframe.radial_velocity_correction(obstime=time) - # else: - # tframe = self.sky_coord_names[name].transform_to(frame) - # vlsr = tframe.radial_velocity_correction(obstime=time) - - # return vlsr.to(u.km / u.s).value - - # def calculate_vlsr_azel(self, az_el, time=None): - # """Takes an AzEl tuple and derives the vlsr from Location - - # Parameters - # ---------- - # az_el : (float, float) - # Azimuth and Elevation - # time : AstroPy Time Obj - # Time of Conversion - - # Returns - # ------- - # float - # vlsr in km/s. - # """ - - # if time is None: - # time = Time.now() - - # az, el = az_el - # start_frame = AltAz( - # obstime=time, location=self.location, alt=el * u.deg, az=az * u.deg - # ) - # end_frame = Galactic() - # result = start_frame.transform_to(end_frame) - # sk1 = SkyCoord(result) - # f1 = AltAz(obstime=time, location=self.location) - # vlsr = sk1.transform_to(f1).radial_velocity_correction(obstime=time) - - # return vlsr.to(u.km/u.s).value def convert_to_gal_coord(self, az_el, time=None): """Converts an AzEl Tuple into a Galactic Tuple from Location @@ -273,15 +212,15 @@ def update_all_az_el(self): transformed.az[index].degree, transformed.alt[index].degree, ) - vlsr = self.calculate_vlsr(transformed[index], time) - self.vlsr_dict[name] = vlsr + #vlsr = self.calculate_vlsr(transformed[index], time) + #self.vlsr_dict[name] = vlsr #deal with annoying things that move against the sky for body in self.bodies: body_coords = get_body(time=time, body=body,location=self.location).transform_to(frame) self.az_el_dict[body] = (body_coords.az.degree, body_coords.alt.degree) - self.vlsr_dict[body] = self.calculate_vlsr(body_coords, time) + #self.vlsr_dict[body] = self.calculate_vlsr(body_coords, time) #and prepredict things (do we actually need this?) @@ -345,8 +284,8 @@ def get_all_azel_time(self): # name, time, AltAz(obstime=time, location=self.location) # ) - def get_all_vlsr(self): - return self.vlsr_dict + #def get_all_vlsr(self): + # return self.vlsr_dict # def get_vlsr(self, name, time_offset=0): #not used From a88097c96910720e3636f82c78f128fcf0e199e8 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 1 Oct 2024 19:14:01 -0400 Subject: [PATCH 59/79] Update daemon.py --- srt/daemon/daemon.py | 1 + 1 file changed, 1 insertion(+) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 739e4a0f..801b49d1 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -282,6 +282,7 @@ def beam_switch(self, object_id): self.ephemeris_cmd_location = object_id self.beam_switch_data = [rotor_loc, pwr_list] + def point_at_object(self, object_id): """Points Antenna Directly at Object, and Sets Up Tracking to Follow it Parameters From 0d005c770942b227a48e685bcffc13a565edce25 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 1 Oct 2024 19:30:06 -0400 Subject: [PATCH 60/79] make rotor loop more responsive while updating celestial coord calcs less often --- srt/daemon/daemon.py | 39 +++++++++++++++++++++++---------------- 1 file changed, 23 insertions(+), 16 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 801b49d1..74cebedd 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -835,7 +835,11 @@ def update_rotor_status(self): Returns ------- None + """ + + last_time = time() + while True: try: current_rotor_cmd_location = self.rotor_cmd_location @@ -850,7 +854,7 @@ def update_rotor_status(self): not azel_within_range( self.rotor_location, current_rotor_cmd_location ) - ) and (time() - start_time) < 10: + ) and (time() - start_time) < 15: past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() #print(past_rotor_location, self.rotor_location) @@ -873,27 +877,30 @@ def update_rotor_status(self): sleep(0.1) else: + past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() - #print(self.rotor_location) - #if not self.rotor_location == past_rotor_location: #we should not do this check, still want to update galactic lat and lon at reasonable cadence - obstime = Time.now() + if (time() - last_time) > 5 : #don't bother recomputing the celestial coordinates so often if we're not actally moving - g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord(self.rotor_location) - self.radio_queue.put(("motor_az", float(self.rotor_location[0]))) - self.radio_queue.put(("motor_el", float(self.rotor_location[1]))) - self.radio_queue.put(("glat", g_lat)) - self.radio_queue.put(("glon", g_lon)) + obstime = Time.now() - #compute vlsr for where we're actually pointed. we don't really care if it's theoretically different for the target object - - azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) - sky_coord = SkyCoord(azel_frame) - self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) - self.radio_queue.put(("vlsr", float(self.current_vlsr))) + g_lat, g_lon = self.ephemeris_tracker.convert_to_gal_coord(self.rotor_location) + self.radio_queue.put(("motor_az", float(self.rotor_location[0]))) + self.radio_queue.put(("motor_el", float(self.rotor_location[1]))) + self.radio_queue.put(("glat", g_lat)) + self.radio_queue.put(("glon", g_lon)) + + #compute vlsr for where we're actually pointed. we don't really care if it's theoretically different for the target object + + azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) + sky_coord = SkyCoord(azel_frame) + self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) + self.radio_queue.put(("vlsr", float(self.current_vlsr))) + + last_time = time() - sleep(1) + sleep(0.05) #make it much more responsive to commands except AssertionError as e: self.log_message(str(e)) From 545133a64821abe129292ce70619859eb7f222a9 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 1 Oct 2024 19:57:10 -0400 Subject: [PATCH 61/79] minor tweak to ephemeris update timing --- srt/daemon/daemon.py | 32 ++++++++++++++------------------ 1 file changed, 14 insertions(+), 18 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 74cebedd..b0fbc4e1 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -796,27 +796,21 @@ def update_ephemeris_location(self): if last_updated_time is None or time() - last_updated_time > 10: last_updated_time = time() self.ephemeris_tracker.update_all_az_el() - self.ephemeris_locations = ( - self.ephemeris_tracker.get_all_azimuth_elevation() - ) - #only update vlsr when we care and only at cadence we update celestial coordinates - #do this in rotor update loop, not here - #self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() + self.ephemeris_locations = (self.ephemeris_tracker.get_all_azimuth_elevation()) + + #only update vlsr when we care and only at cadence we update celestial coordinates + #do this in rotor update loop, not here + #self.ephemeris_vlsr = self.ephemeris_tracker.get_all_vlsr() + + self.ephemeris_time_locs = (self.ephemeris_tracker.get_all_azel_time()) - self.ephemeris_time_locs = ( - self.ephemeris_tracker.get_all_azel_time() - ) if self.ephemeris_cmd_location is not None: - new_rotor_destination = self.ephemeris_locations[ - self.ephemeris_cmd_location - ] + new_rotor_destination = self.ephemeris_locations[self.ephemeris_cmd_location] #self.current_vlsr = self.ephemeris_vlsr[self.ephemeris_cmd_location] - new_rotor_cmd_location = tuple( - map(add, new_rotor_destination, self.rotor_offsets) - ) + new_rotor_cmd_location = tuple(map(add, new_rotor_destination, self.rotor_offsets)) + if self.rotor.angles_within_bounds( - *new_rotor_destination - ) and self.rotor.angles_within_bounds(*new_rotor_cmd_location): + *new_rotor_destination) and self.rotor.angles_within_bounds(*new_rotor_cmd_location): self.rotor_destination = new_rotor_destination self.rotor_cmd_location = new_rotor_cmd_location else: @@ -825,7 +819,9 @@ def update_ephemeris_location(self): ) self.ephemeris_cmd_location = None - sleep(1) + sleep(1) + + sleep(0.1) def update_rotor_status(self): """Periodically Sets Rotor Azimuth and Elevation and Fetches New Antenna Position From bfc8ad48980feb2c9473356a3a00459e0aedab92 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 2 Oct 2024 00:11:04 +0000 Subject: [PATCH 62/79] make status refresh rate and UI refresh rate the same --- config/config.yaml | 2 +- srt/daemon/daemon.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/config/config.yaml b/config/config.yaml index a0c509e4..a4ddb392 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -49,4 +49,4 @@ RUN_HEADLESS: No DASHBOARD_PORT: 8080 DASHBOARD_HOST: 0.0.0.0 DASHBOARD_DOWNLOADS: Yes -DASHBOARD_REFRESH_MS: 1000 +DASHBOARD_REFRESH_MS: 500 diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index b0fbc4e1..7bfb12f9 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -948,7 +948,7 @@ def update_status(self): "cal_state": self.radio_calibrator_state, } status_socket.send_json(status) - sleep(0.2) + sleep(self.dashboard_refresh_rate) def update_radio_settings(self): """Coordinates Sending XMLRPC Commands to the GNU Radio Script From 6ad9a12c34291c3dfb174c1168e98d220bc983c7 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 8 Oct 2024 09:40:21 -0400 Subject: [PATCH 63/79] Update daemon.py make stow comand call az/el pointing instead of doing its own thing --- srt/daemon/daemon.py | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 7bfb12f9..a5cec1e8 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -331,7 +331,7 @@ def point_at_azel(self, az, el): #sky_coord = SkyCoord(azel_frame) - self.ephemeris_cmd_location = None + self.ephemeris_cmd_location = None #clear tracking command self.rotor_offsets = (0.0, 0.0) # Send az and el angles to sources track for the radio self.radio_queue.put(("soutrack", f"azel_{az}_{el}")) @@ -342,6 +342,8 @@ def point_at_azel(self, az, el): self.rotor_destination = new_rotor_destination self.rotor_cmd_location = new_rotor_cmd_location while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + self.rotor_destination = new_rotor_destination + self.rotor_cmd_location = new_rotor_cmd_location sleep(0.1) else: @@ -439,12 +441,15 @@ def stow(self): None """ self.ephemeris_cmd_location = None - self.radio_queue.put(("soutrack", "at_stow")) - self.rotor_offsets = (0.0, 0.0) - self.rotor_destination = self.stow_location - self.rotor_cmd_location = self.stow_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): - sleep(0.1) + self.point_at_azel(self.stow_location[0], self.stow_location[1]) + + #self.ephemeris_cmd_location = None + #self.radio_queue.put(("soutrack", "at_stow")) + #self.rotor_offsets = (0.0, 0.0) + #self.rotor_destination = self.stow_location + #self.rotor_cmd_location = self.stow_location + #while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + # sleep(0.1) def calibrate(self): """Runs Calibration Processing and Pushes New Values to Processing Script From 923ee8253bbc5105fa7106d28b7fbae1c4b0d8c4 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 8 Oct 2024 13:00:41 -0400 Subject: [PATCH 64/79] Update monitor_page.py disable last bit of glitchy recording alert temporarily until I can fix it properly so the recording dropdown will work --- srt/dashboard/layouts/monitor_page.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 260dd825..8505d794 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1567,11 +1567,13 @@ def offset_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): Input("record-btn-yes", "n_clicks"), Input("record-btn-no", "n_clicks"), ], - [State("record-modal", "is_open"), State("record-options", - "value"), State("recording-alert", "is_open")], + [ + State("record-modal", "is_open"), + State("record-options","value"), + #State("recording-alert", "is_open")], ) def record_click_func( - n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option, is_open_alert + n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option#, is_open_alert ): ctx = dash.callback_context if not ctx.triggered: @@ -1580,10 +1582,10 @@ def record_click_func( button_id = ctx.triggered[0]["prop_id"].split(".")[0] if button_id == "record-btn-yes": command_thread.add_to_queue(f"record {record_option}") - print("alert") + #print("alert") if n_clicks_yes or n_clicks_no or n_clicks_btn: - print("open") + #print("open") return not is_open return is_open From 47b5852744af6dd5312af1bad4f113351e68c664 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 8 Oct 2024 13:02:54 -0400 Subject: [PATCH 65/79] Update monitor_page.py fix syntax error introduced in previous commit --- srt/dashboard/layouts/monitor_page.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 8505d794..01ae3651 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1570,7 +1570,8 @@ def offset_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): [ State("record-modal", "is_open"), State("record-options","value"), - #State("recording-alert", "is_open")], + #State("recording-alert", "is_open") + ], ) def record_click_func( n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option#, is_open_alert From 41778167f2332b16d1e8c7b03202129c3b4b297a Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Mon, 14 Oct 2024 18:09:38 -0400 Subject: [PATCH 66/79] Added support for RaDec and Galactic Coordinate pointing commands (#1) * added capability for tracking arbitrary icrs and galactic coordinates. still only using az/el for now until we can have more advanced tracking code though * typo fixes plus handling an inadvertently introduced instability in the rotor control command handling * changed arbitrary tracking point structure to not appear on UI * fixed to hopefully prevent collisions between ephemeris computation and target tracking * seems to be working properly now * split target tracking into separate thread and updated radec and azel commands to fully avoid collisions (and fixed a fiddly issue with n point scans * fixed angle within range check in utilities to accept angles at antenna limit otherwise it freezes at zero azimuth * commented last vestige of glitchy recording alert function for now in hopes it fixes recording dropdown * trying to fix bug where stow/az el pointing commands sometimes fail after tracking an object --------- Co-authored-by: JLab Account on Scotty Server --- srt/daemon/daemon.py | 160 ++++++++++++++++++------- srt/daemon/utilities/functions.py | 2 +- srt/daemon/utilities/object_tracker.py | 42 ++++++- srt/dashboard/layouts/monitor_page.py | 2 +- 4 files changed, 156 insertions(+), 50 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index a5cec1e8..282cf5c3 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -199,6 +199,7 @@ def n_point_scan(self, object_id, grid_size=5): self.radio_queue.put(("soutrack", object_id)) scan_center = self.ephemeris_locations[object_id] + self.ephemeris_cmd_location = object_id #tell tracking process to follow scan center # Send vlsr to radio queue #cur_vlsr = self.ephemeris_vlsr[object_id] @@ -226,7 +227,7 @@ def n_point_scan(self, object_id, grid_size=5): new_rotor_offsets = (az_dif, el_dif) if self.rotor.angles_within_bounds(*scan_center): - self.rotor_destination = scan_center + #self.rotor_destination = self.ephemeris_locations[object_id] #this line is probably redundant self.point_at_offset(*new_rotor_offsets) rotor_loc.append(self.rotor_location) sleep(5) @@ -327,11 +328,13 @@ def point_at_azel(self, az, el): #obstime = Time.now() - #azel_frame = AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=el * u.deg, az=az * u.deg) - #sky_coord = SkyCoord(azel_frame) + #sky_coord = SkyCoord(AltAz(obstime=obstime, location=self.ephemeris_tracker.location, alt=el * u.deg, az=az * u.deg)) + #self.ephemeris_tracker.target=sky_coord + if self.ephemeris_cmd_location is not None: + self.ephemeris_cmd_location = None #clear tracking command + sleep(0.05) #give the ephemeris tracker time to finish and stop causing trouble - self.ephemeris_cmd_location = None #clear tracking command self.rotor_offsets = (0.0, 0.0) # Send az and el angles to sources track for the radio self.radio_queue.put(("soutrack", f"azel_{az}_{el}")) @@ -349,7 +352,7 @@ def point_at_azel(self, az, el): self.log_message(f"Object at {new_rotor_cmd_location} Not in Motor Bounds") - def point_at_galactic(self, l_pos, b_pos, duration): + def point_at_galactic(self, l_pos, b_pos): """Points Antenna at a Specific Galactic longitude and lattitude Parameters @@ -364,21 +367,46 @@ def point_at_galactic(self, l_pos, b_pos, duration): Returns ------- None - """ + """ + + #clear preexisting track (prevents target update collisions) + self.ephemeris_cmd_location = None #define a skycoord object with galactic coord info sky_coord = SkyCoord(l_pos, b_pos, frame='galactic', unit=u.deg, location=self.ephemeris_tracker.location) + self.ephemeris_tracker.target=sky_coord + object_id = "target" + sleep(0.05) + - if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): - #rotor is smart enough to directly handle the command + #if (self.motor_type == "W1XM_BIG_DISH"): + #rotor is smart enough to directly handle the command, need to eventually restructure so we can pass it nicely - self.log_message("direct ra dec coordinate commands not yet supported for your rotor") - else: + # self.log_message("direct galactic coordinate commands not yet supported for your rotor. using standard tracking") + #else: #rotor needs command converted to az-el - self.log_message("direct galactic coordinate commands not yet supported for your rotor") + # self.log_message("direct galactic coordinate commands not yet supported for your rotor. using standard tracking") + + self.rotor_offsets = (0.0, 0.0) + self.radio_queue.put(("soutrack", f"radec_{l_pos}_{b_pos}")) + + azel_frame = AltAz(obstime=Time.now(), location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) + target_azel = sky_coord.transform_to(azel_frame) + new_rotor_destination = (target_azel.az.degree, target_azel.alt.degree) + new_rotor_cmd_location = tuple(map(add, new_rotor_destination, self.rotor_offsets)) + + if self.rotor.angles_within_bounds(*new_rotor_cmd_location): + self.ephemeris_cmd_location = object_id + self.rotor_destination = new_rotor_cmd_location + self.rotor_cmd_location = new_rotor_cmd_location + while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + sleep(0.1) + else: + self.log_message(f"Object {object_id} Not in Motor Bounds") + self.ephemeris_cmd_location = None - def point_at_radec(self, ra_pos, dec_pos, duration): + def point_at_radec(self, ra_pos, dec_pos): """Points Antenna at a specific ICRS coordinate in Ra Dec (Bigdish uses J2000) @@ -396,16 +424,30 @@ def point_at_radec(self, ra_pos, dec_pos, duration): None """ - #define a skycoord object with galactic coord info + #clear preexisting track (prevents target update collisions) + self.ephemeris_cmd_location = None - sky_coord = SkyCoord(ra_pos, dec_pos, frame='icrs', unit=u.deg, location=self.ephemeris_tracker.location) - - if (motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value): - #rotor is smart enough to directly handle the command - self.log_message("direct ra dec coordinate commands not yet supported for your rotor") + sky_coord = SkyCoord(ra_pos, dec_pos, frame='icrs', unit=u.deg, location=self.ephemeris_tracker.location) + self.ephemeris_tracker.target=sky_coord + object_id = "target" + + self.rotor_offsets = (0.0, 0.0) + self.radio_queue.put(("soutrack", f"radec_{ra_pos}_{dec_pos}")) + + azel_frame = AltAz(obstime=Time.now(), location=self.ephemeris_tracker.location, alt=self.rotor_location[1] * u.deg, az=self.rotor_location[0] * u.deg) + target_azel = sky_coord.transform_to(azel_frame) + new_rotor_destination = (target_azel.az.degree, target_azel.alt.degree) + new_rotor_cmd_location = tuple(map(add, new_rotor_destination, self.rotor_offsets)) + + if self.rotor.angles_within_bounds(*new_rotor_cmd_location): + self.ephemeris_cmd_location = object_id + self.rotor_destination = new_rotor_cmd_location + self.rotor_cmd_location = new_rotor_cmd_location + while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + sleep(0.1) else: - #rotor needs command converted to az-el - self.log_message("direct ra dec coordinate commands not yet supported for your rotor") + self.log_message(f"Object {object_id} Not in Motor Bounds") + self.ephemeris_cmd_location = None def point_at_offset(self, az_off, el_off): """From the Current Object or Position Pointed At, Move to an Offset of That Location @@ -434,13 +476,13 @@ def point_at_offset(self, az_off, el_off): self.log_message(f"Offset {new_rotor_offsets} Out of Bounds") def stow(self): - """Moves the Antenna Back to Its Stow Location + """Moves the Antenna Back to its Stow Location Returns ------- None """ - self.ephemeris_cmd_location = None + self.point_at_azel(self.stow_location[0], self.stow_location[1]) #self.ephemeris_cmd_location = None @@ -809,25 +851,48 @@ def update_ephemeris_location(self): self.ephemeris_time_locs = (self.ephemeris_tracker.get_all_azel_time()) + #sleep(0.1) + + def update_target_position(self): + """Update position of point we are tracking separately from the display ephemeris + + Is Operated as an Infinite Looping Thread Function + + Returns + ------- + None + """ + last_updated_time = None + #last_ephemeris_cmd_location = None + tracking_update_time = 5 + + + while True: if self.ephemeris_cmd_location is not None: - new_rotor_destination = self.ephemeris_locations[self.ephemeris_cmd_location] - #self.current_vlsr = self.ephemeris_vlsr[self.ephemeris_cmd_location] - new_rotor_cmd_location = tuple(map(add, new_rotor_destination, self.rotor_offsets)) - - if self.rotor.angles_within_bounds( - *new_rotor_destination) and self.rotor.angles_within_bounds(*new_rotor_cmd_location): - self.rotor_destination = new_rotor_destination - self.rotor_cmd_location = new_rotor_cmd_location - else: - self.log_message( - f"Object {self.ephemeris_cmd_location} moved out of motor bounds" - ) - self.ephemeris_cmd_location = None - sleep(1) + if ((last_updated_time is None) or (time() - last_updated_time > tracking_update_time)): + #last_ephemeris_cmd_location = self.ephemeris_cmd_location + last_updated_time = time() + + self.ephemeris_tracker.update_track(self.ephemeris_cmd_location) + new_rotor_destination = self.ephemeris_tracker.get_track_azimuth_elevation(self.ephemeris_cmd_location) + new_rotor_cmd_location = tuple(map(add, new_rotor_destination, self.rotor_offsets)) + + if self.rotor.angles_within_bounds( + *new_rotor_destination) and self.rotor.angles_within_bounds(*new_rotor_cmd_location): + self.rotor_destination = new_rotor_destination + self.rotor_cmd_location = new_rotor_cmd_location + + else: + self.log_message(f"Object {self.ephemeris_cmd_location} moved out of motor bounds") + self.ephemeris_cmd_location = None sleep(0.1) + + + + def update_rotor_status(self): """Periodically Sets Rotor Azimuth and Elevation and Fetches New Antenna Position @@ -879,10 +944,15 @@ def update_rotor_status(self): sleep(0.1) else: - past_rotor_location = self.rotor_location - self.rotor_location = self.rotor.get_azimuth_elevation() + #past_rotor_location = self.rotor_location + #self.rotor_location = self.rotor.get_azimuth_elevation() if (time() - last_time) > 5 : #don't bother recomputing the celestial coordinates so often if we're not actally moving + self.rotor.set_azimuth_elevation(*current_rotor_cmd_location) #always reissue pointing commands periodically and let rotor decide whether to adjust + sleep(0.1) + + past_rotor_location = self.rotor_location + self.rotor_location = self.rotor.get_azimuth_elevation() obstime = Time.now() @@ -901,7 +971,9 @@ def update_rotor_status(self): last_time = time() - sleep(0.05) #make it much more responsive to commands + sleep(0.1) #make it much more responsive to commands + #aparrently making this loop too fast causes stability issues. prolly need to tweak rotor level code a bit to not + #crash and burn ir a read comes in before it has a status update request comes before it has new data except AssertionError as e: self.log_message(str(e)) @@ -998,8 +1070,9 @@ def srt_daemon_main(self): # Create Infinite Looping Threads ephemeris_tracker_thread = Thread( - target=self.update_ephemeris_location, daemon=True - ) + target=self.update_ephemeris_location, daemon=True) + target_tracking_thread = Thread( + target=self.update_target_position, daemon=True) rotor_pointing_thread = Thread( target=self.update_rotor_status, daemon=True) command_queueing_thread = Thread( @@ -1048,6 +1121,7 @@ def srt_daemon_main(self): # Start Infinite Looping Update Threads ephemeris_tracker_thread.start() + target_tracking_thread.start() rotor_pointing_thread.start() command_queueing_thread.start() status_thread.start() @@ -1117,19 +1191,15 @@ def srt_daemon_main(self): float(command_parts[1]), float(command_parts[2]), ) - #for bigdish enable temporary bypass of SRT command and control to directly point dish elif command_name == "galactic": self.point_at_galactic( float(command_parts[1]), float(command_parts[2]), - float(command_parts[3]), ) - #for bigdish enable temporary bypass of SRT command and control to directly point dish elif command_name == "radec": self.point_at_radec( float(command_parts[1]), float(command_parts[2]), - float(command_parts[2]), ) elif command_name == "offset": self.point_at_offset( diff --git a/srt/daemon/utilities/functions.py b/srt/daemon/utilities/functions.py index 1dfc5118..1bd5e6c9 100644 --- a/srt/daemon/utilities/functions.py +++ b/srt/daemon/utilities/functions.py @@ -24,7 +24,7 @@ def angle_within_range(actual_angle, desired_angle, bounds=0.1): bool Whether Angles Were Within Threshold """ - return abs(actual_angle - desired_angle) < bounds + return abs(actual_angle - desired_angle) <= bounds def azel_within_range(actual_azel, desired_azel, bounds=(0.1, 0.1)): diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py index 487f2015..a16908c4 100644 --- a/srt/daemon/utilities/object_tracker.py +++ b/srt/daemon/utilities/object_tracker.py @@ -86,15 +86,19 @@ def __init__( ) self.sky_coords = SkyCoord( - ra=sky_coords_ra * u.deg, dec=sky_coords_dec * u.deg, frame=CIRS, location=self.location - ) + ra=sky_coords_ra * u.deg, dec=sky_coords_dec * u.deg, frame=CIRS, location=self.location) + + self.bodies = ["Sun", "Moon", "Jupiter"] #list bodies we want to track so other functions can grab these (really should pull in from config file) + ##variable to hold a target skycoord object + + self.target = SkyCoord(ra= 0*u.deg, dec= 0*u.deg,frame='icrs', location=self.location) - self.bodies = ["Sun", "Moon"] #list bodies we want to track so other functions can grab these (really should pull in from config file) self.latest_time = None self.refresh_time = refresh_time * u.second self.az_el_dict = {} + self.target_coords =(0,0) #separate thing just to store target to so we don't display the point in the gui # self.vlsr_dict = {} # self.time_interval_dict = {} self.time_interval_dict = self.inital_azeltime() @@ -243,6 +247,38 @@ def update_all_az_el(self): self.latest_time = time + def update_track(self, object_id): + + time = Time.now() + frame = AltAz(obstime=time, location=self.location) + + if object_id == "target": + transformed = self.target.transform_to(frame) + self.target_coords = ( + transformed.az.degree, + transformed.alt.degree + ) + + elif object_id in self.sky_coord_names: #then this is a normal programmed object and we'll just rerun the usual calculation only for that point + index = self.sky_coord_names[object_id] + transformed = self.sky_coords[index].transform_to(frame) + self.target_coords = ( + transformed.az.degree, + transformed.alt.degree + ) + + elif object_id in self.bodies: #annoying things like planets + body_coords = get_body(time=time, body=object_id,location=self.location).transform_to(frame) + self.target_coords = (body_coords.az.degree, body_coords.alt.degree) + + else: + return + + def get_track_azimuth_elevation(self,object_id): #for tracking updates + + return self.target_coords + + def get_all_azimuth_elevation(self): """Returns Dictionary Mapping the Objects to their Current AzEl Coordinates diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index 01ae3651..c15c07ae 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -1574,7 +1574,7 @@ def offset_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): ], ) def record_click_func( - n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option#, is_open_alert + n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option #, is_open_alert ): ctx = dash.callback_context if not ctx.triggered: From 7698fae2b8aab4091c957c8dcea33499487e1e2f Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Mon, 14 Oct 2024 18:49:43 -0400 Subject: [PATCH 67/79] Update command_files.md added newer commands that are supported --- docs/command_files.md | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/docs/command_files.md b/docs/command_files.md index a0b02a7e..1df02712 100644 --- a/docs/command_files.md +++ b/docs/command_files.md @@ -8,28 +8,38 @@ The SRT software accepts commands in order to change settings at runtime as well | Command | Parameters | Notes |Info | |--------------|------------|-------|--------------------------------------------| | * | Any text | 1 | Makes Line a Comment | -| stow | None | | Sends the Antenna to Stow | +| azel | [az] [el] | | Points at Azimuth 'az', Elevation 'el' | +| galactic | [lat] [lon]| | Points at galactic coordinates and tracks | +| radec | [ra] [dec] | 7 | Points at ICRS coordinates and tracks | | cal | None | | Sends the Antenna to Calibration Position | -| calibrate | None | 2 | Saves Current Spec as Calibration Data | +| calibrate | None | 2 | Runs antenna calibration routine | +| calon | None | 6 | Enable calibration noise source | +| caloff | None | 6 | Disable calibration noise source | +| freq | [cf] | | Sets Center Frequency in MHz to 'cf' | +| n | None | | Run an N point scan and display results | +| npointset | [n] | | set number of points to a grid side in n point scan | | quit | None | 3 | Stows and Gracefully Closes Daemon | +| rf_gain | [dB] | | Set Rf gain in SDR | | record | [filename] | 4 | Starts Saving into File of Name 'filename' | | roff | None | | Ends Current Recording if Applicable | -| azel | [az] [el] | | Points at Azimuth 'az', Elevation 'el' | | offset | [az] [el] | | Offsets from Current Object by 'az', 'el' | -| freq | [cf] | | Sets Center Frequency in MHz to 'cf' | | samp | [sf] | | Sets Sampling Frequency in MHz to 'sf' | +| stow | None | | Sends the Antenna to Stow | | wait | [time] | | Stops Execution and Waits for 'time' Secs. | | [time] | None | | Waits for 'time' Seconds | -| LST:hh:mm:ss | None | | Waits Until Next Time hh:mm:ss in UTC | -| Y:D:H:M:S | None | | Waits Until Year:DayOfYear:Hour:Minute:Sec | +| wait_utc_hms | hh:mm:ss | | Waits Until Next Time hh:mm:ss in UTC | +| wait_utc_iso | Y-m-dTH:M:S.f| 8 | Waits Until Year-Month-DayTHour:Minute:Sec | | [name] | [n] or [b] | 5 | Points Antenna at Object named 'name' | Additional Notes: 1. Only is considered a comment if the line starts with '\*'. - 2. Calibration takes samples at its current location (which should typically be 'cal') and uses those to determine the shape of the band-pass filter and eliminate it from the calibrated spectra. Calibration should therefore by done against a non-source object of known noise temperature. + 2. Calibration takes samples at its current location (which should typically be 'cal') and uses those to determine the shape of the band-pass filter and eliminate it from the calibrated spectra. Calibration should therefore by done against a non-source object of known noise temperature. The exat behavior is dependent on the type of calibrator programmed in the config. 3. Unlike the previous SRT software, 'quit' both stows and quits (ends the daemon process). After this is done, it will be necessary to restart the daemon process from command line or via the Dashboard 'Start Daemon' button. 4. Currently, three different file types are supported, and the type used is determined by the file extension of the name given. FITS (Calibrated Spectra) is used when the file ends in '.fits', rad (Calibrated Spectra) is used when it ends in '.rad', and Digital RF (Raw I/Q Samples) is used when the name lacks a file ending. If no filename is provided, Digital RF will be used with an auto-generated name. In order to use rad or FITS with an autogenerated name, use "\*.rad" or "\*.fits" respectively. 5. The names used for pointing at objects are set by the 'sky_coords.csv' file, which is further documented in the config folder portion of the docs. By default, 'Sun' and 'Moon' are already loaded. + 6. calon and caloff commands are valid only for antennas with some form of noise injection or dicke switching. + 7. ICRS coordinates, expects decimal degrees for both Ra and Dec + 8. will accept standard iso formatted utc timestamp to any precision ##### Building Command Files From 472008f975a5aca51e03f829a74ee83a07b42db7 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Mon, 14 Oct 2024 20:03:11 -0400 Subject: [PATCH 68/79] Update command_files.md *fixed mistake in galactic coordinate order --- docs/command_files.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/command_files.md b/docs/command_files.md index 1df02712..706af056 100644 --- a/docs/command_files.md +++ b/docs/command_files.md @@ -9,7 +9,7 @@ The SRT software accepts commands in order to change settings at runtime as well |--------------|------------|-------|--------------------------------------------| | * | Any text | 1 | Makes Line a Comment | | azel | [az] [el] | | Points at Azimuth 'az', Elevation 'el' | -| galactic | [lat] [lon]| | Points at galactic coordinates and tracks | +| galactic | [l] [b]| | Points at galactic coordinates and tracks | | radec | [ra] [dec] | 7 | Points at ICRS coordinates and tracks | | cal | None | | Sends the Antenna to Calibration Position | | calibrate | None | 2 | Runs antenna calibration routine | From 11d4e368ce187caf4b38be1b713bb8b97f3128e5 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Mon, 14 Oct 2024 20:24:57 -0400 Subject: [PATCH 69/79] Add Celestial Coordinate UI commands (#2) * updated UI pointing command to enable celestial target entry * fixed syntax error --- srt/dashboard/layouts/monitor_page.py | 73 ++++++++++++++++++++++----- 1 file changed, 60 insertions(+), 13 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index c15c07ae..e5f1a9ee 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -499,23 +499,40 @@ def generate_popups(software): dbc.Modal( [ - dbc.ModalHeader("Enter Azimuth and Elevation"), + dbc.ModalHeader("Enter Pointing Coordinates"), dbc.ModalBody( [ dcc.Input( - id="azimuth", + id="val1", type="number", debounce=True, - placeholder="Azimuth", + placeholder="Az/RA/l", ), dcc.Input( - id="elevation", + id="val2", type="number", debounce=True, - placeholder="Elevation", + placeholder="El/Dec/b", + ), + dcc.RadioItems( + options=[ + {"label": "Az/El", + "value": "AzEl"}, + { + "label": "Ra/Dec", + "value": "RaDec", + }, + { + "label": "Galactic", + "value": "Galactic", + }, + ], + id="coord-options", + value="", ), ] ), + dbc.ModalFooter( [ dbc.Button( @@ -882,7 +899,8 @@ def generate_layout(software): # ], "Antenna": [ dbc.DropdownMenuItem("Stow", id="btn-stow"), - dbc.DropdownMenuItem("Set AzEl", id="btn-point-azel"), + #dbc.DropdownMenuItem("Set AzEl", id="btn-point-azel"), + dbc.DropdownMenuItem("Set Coordinates", id="btn-point-coords"), dbc.DropdownMenuItem("Set Offsets", id="btn-set-offset"), dbc.DropdownMenuItem("Set N-point size", id="btn-set-npoint"), ], @@ -1412,32 +1430,61 @@ def coords_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, lat, lon return not is_open return is_open + # @ app.callback( + # Output("point-modal", "is_open"), + # [ + # Input("btn-point-azel", "n_clicks"), + # Input("point-btn-yes", "n_clicks"), + # Input("point-btn-no", "n_clicks"), + # ], + # [ + # State("point-modal", "is_open"), + # State("azimuth", "value"), + # State("elevation", "value"), + # ], + # ) + # def point_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): + # ctx = dash.callback_context + # if not ctx.triggered: + # return is_open + # else: + # button_id = ctx.triggered[0]["prop_id"].split(".")[0] + # if button_id == "point-btn-yes": + # command_thread.add_to_queue(f"azel {az} {el}") + # if n_clicks_yes or n_clicks_no or n_clicks_btn: + # return not is_open + # return is_open + @ app.callback( Output("point-modal", "is_open"), [ - Input("btn-point-azel", "n_clicks"), + Input("btn-point-coords", "n_clicks"), Input("point-btn-yes", "n_clicks"), Input("point-btn-no", "n_clicks"), ], [ State("point-modal", "is_open"), - State("azimuth", "value"), - State("elevation", "value"), + State("val1", "value"), + State("val2", "value"), + State("coord-options", "value"), ], ) - def point_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): + def point_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, val1, val2, coord_option): ctx = dash.callback_context if not ctx.triggered: return is_open else: button_id = ctx.triggered[0]["prop_id"].split(".")[0] if button_id == "point-btn-yes": - command_thread.add_to_queue(f"azel {az} {el}") + if coord_option == "RaDec": + command_thread.add_to_queue(f"radec {val1} {val2}") + elif coord_option == "Galactic": + command_thread.add_to_queue(f"galactic {val1} {val2}") + else: #coord_option == "AzEl": + command_thread.add_to_queue(f"azel {val1} {val2}") if n_clicks_yes or n_clicks_no or n_clicks_btn: return not is_open return is_open - - @app.callback( Output("n-point-modal", "is_open"), From 752d152f13f78b50a502875caf04b3b98f87d665 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Mon, 14 Oct 2024 21:15:23 -0400 Subject: [PATCH 70/79] reenabled recording alert code from haystack, need to debug. (#3) --- srt/dashboard/layouts/monitor_page.py | 80 +++++++++++---------------- 1 file changed, 31 insertions(+), 49 deletions(-) diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py index e5f1a9ee..c81e525e 100644 --- a/srt/dashboard/layouts/monitor_page.py +++ b/srt/dashboard/layouts/monitor_page.py @@ -928,8 +928,8 @@ def generate_layout(software): layout = html.Div( [ generate_navbar(drop_down_buttons_vsrt), - #dbc.Alert("Recording", color="danger", - # id="recording-alert", is_open=False), + dbc.Alert("Recording", color="danger", + id="recording-alert", is_open=False), generate_first_row(), generate_second_row(), generate_third_row(), @@ -941,8 +941,8 @@ def generate_layout(software): layout = html.Div( [ generate_navbar(drop_down_buttons_srt), - #dbc.Alert("Recording", color="danger", - # id="recording-alert", is_open=False), + dbc.Alert("Recording", color="danger", + id="recording-alert", is_open=False), generate_first_row(), generate_srt_azel(), generate_srt_second_row(), @@ -1429,31 +1429,6 @@ def coords_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, lat, lon if n_clicks_yes or n_clicks_no or n_clicks_btn: return not is_open return is_open - - # @ app.callback( - # Output("point-modal", "is_open"), - # [ - # Input("btn-point-azel", "n_clicks"), - # Input("point-btn-yes", "n_clicks"), - # Input("point-btn-no", "n_clicks"), - # ], - # [ - # State("point-modal", "is_open"), - # State("azimuth", "value"), - # State("elevation", "value"), - # ], - # ) - # def point_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): - # ctx = dash.callback_context - # if not ctx.triggered: - # return is_open - # else: - # button_id = ctx.triggered[0]["prop_id"].split(".")[0] - # if button_id == "point-btn-yes": - # command_thread.add_to_queue(f"azel {az} {el}") - # if n_clicks_yes or n_clicks_no or n_clicks_btn: - # return not is_open - # return is_open @ app.callback( Output("point-modal", "is_open"), @@ -1617,11 +1592,11 @@ def offset_click_func(n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, az, el): [ State("record-modal", "is_open"), State("record-options","value"), - #State("recording-alert", "is_open") + State("recording-alert", "is_open") ], ) def record_click_func( - n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option #, is_open_alert + n_clicks_btn, n_clicks_yes, n_clicks_no, is_open, record_option, is_open_alert ): ctx = dash.callback_context if not ctx.triggered: @@ -1637,24 +1612,26 @@ def record_click_func( return not is_open return is_open - #@ app.callback( - # Output("recording-alert", "is_open"), - # [Input("record-btn-yes", "n_clicks"), - # Input("btn-stop-record", "n_clicks")], - # [], - #) - #def record_alert_func(n_clicks_start, n_clicks_stop): - # ctx = dash.callback_context - # if not ctx.triggered: - # return False - # else: - # if not n_clicks_start: - # return False - # if not n_clicks_stop: - # return True - # if n_clicks_start == n_clicks_stop: - # return False - # return True + @ app.callback( + Output("recording-alert", "is_open"), + [ + Input("record-btn-yes", "n_clicks"), + Input("btn-stop-record", "n_clicks") + ], + [], + ) + def record_alert_func(n_clicks_start, n_clicks_stop): + ctx = dash.callback_context + if not ctx.triggered: + return False + else: + if not n_clicks_start: + return False + if not n_clicks_stop: + return True + if n_clicks_start == n_clicks_stop: + return False + return True @ app.callback( Output("cmd-file-modal", "is_open"), @@ -1727,6 +1704,9 @@ def run_srt_daemon(configuration_dir, configuration_dict): Input("btn-calon", "n_clicks"), Input("btn-caloff", "n_clicks"), ], + [ + State("recording-alert", "is_open") + ] ) def cmd_button_pressed( n_clicks_stow, @@ -1735,6 +1715,7 @@ def cmd_button_pressed( n_clicks_calibrate, n_clicks_calon, n_clicks_caloff, + is_open, ): ctx = dash.callback_context if not ctx.triggered: @@ -1745,6 +1726,7 @@ def cmd_button_pressed( command_thread.add_to_queue("stow") if button_id == "btn-stop-record": command_thread.add_to_queue("roff") + return not is_open elif button_id == "btn-quit": command_thread.add_to_queue("quit") elif button_id == "btn-calibrate": From 5df9fca5592361cf00e11ad8aa79f4c9f0b8b53c Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Tue, 15 Oct 2024 22:54:05 +0000 Subject: [PATCH 71/79] fixed cygnus A coordinates to match Simbad database --- config/sky_coords.csv | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/config/sky_coords.csv b/config/sky_coords.csv index 7c7a7d5e..5f7d3964 100644 --- a/config/sky_coords.csv +++ b/config/sky_coords.csv @@ -6,7 +6,7 @@ fk4,23 21 12,58 44 00,Cass fk4,17 42 54,-28 50 00,SgrA fk4,06 29 12,04 57 00,Rosett fk4,18 17 30,-16 18 00,M17 -fk4,20 27 00,41 00 00,CygEMN +fk4,19 57 44,40 35 46,CygEMN fk4,21 12 00,48 00 00,G90 fk4,05 40 00,29 00 00,G180 fk4,12 48 00,28 00 00,GNpole @@ -50,4 +50,4 @@ galactic,310,0,G310 galactic,320,0,G320 galactic,330,0,G330 galactic,340,0,G340 -galactic,350,0,G350 \ No newline at end of file +galactic,350,0,G350 From 27fa63dbe93a288d4a3afec01c66dd32c0386ec2 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 15 Oct 2024 19:28:05 -0400 Subject: [PATCH 72/79] add a digit to the position readouts --- srt/dashboard/app.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/srt/dashboard/app.py b/srt/dashboard/app.py index 1fff81a1..d93dde1d 100644 --- a/srt/dashboard/app.py +++ b/srt/dashboard/app.py @@ -306,12 +306,12 @@ def update_status_display(n): else: status_string = f""" #### {status_string} - - Location Lat, Long: {lat:.1f}, {lon:.1f} deg - - Motor Az, El: {az:.1f}, {el:.1f} deg - - Motor Offsets: {az_offset:.1f}, {el_offset:.1f} deg + - Location Lat, Long: {lat:.2f}, {lon:.2f} deg + - Motor Az, El: {az:.2f}, {el:.2f} deg + - Motor Offsets: {az_offset:.2f}, {el_offset:.2f} deg - Center Frequency: {cf / pow(10, 6)} MHz - Bandwidth: {bandwidth / pow(10, 6)} MHz - - VLSR: {vlsr:.1f} km/s + - VLSR: {vlsr:.2f} km/s """ return status_string From 25a6858f20206971d50c49bbc92b96f01d8c09a6 Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 16 Oct 2024 00:04:22 +0000 Subject: [PATCH 73/79] reinstated separate cygEMN position --- config/sky_coords.csv | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/config/sky_coords.csv b/config/sky_coords.csv index 5f7d3964..b8e15d47 100644 --- a/config/sky_coords.csv +++ b/config/sky_coords.csv @@ -6,7 +6,8 @@ fk4,23 21 12,58 44 00,Cass fk4,17 42 54,-28 50 00,SgrA fk4,06 29 12,04 57 00,Rosett fk4,18 17 30,-16 18 00,M17 -fk4,19 57 44,40 35 46,CygEMN +fk4,19 57 44,40 35 46,CygA +fk4,20 27 00,41 00 00,CygEMN fk4,21 12 00,48 00 00,G90 fk4,05 40 00,29 00 00,G180 fk4,12 48 00,28 00 00,GNpole From bab758994ea4347c4d2e89879962f87f83c1a992 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 22 Oct 2024 20:52:57 -0400 Subject: [PATCH 74/79] fix bounds check to be modulo 360 degrees so zero crossover doesn't mess it up --- srt/daemon/utilities/functions.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/srt/daemon/utilities/functions.py b/srt/daemon/utilities/functions.py index 1bd5e6c9..4fa64b4d 100644 --- a/srt/daemon/utilities/functions.py +++ b/srt/daemon/utilities/functions.py @@ -24,7 +24,7 @@ def angle_within_range(actual_angle, desired_angle, bounds=0.1): bool Whether Angles Were Within Threshold """ - return abs(actual_angle - desired_angle) <= bounds + return abs(actual_angle - desired_angle) % 360.0 <= bounds def azel_within_range(actual_azel, desired_azel, bounds=(0.1, 0.1)): From 7e4573a66f70222e4932933f085fcff390ea8fe5 Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Mon, 4 Nov 2024 17:51:22 -0500 Subject: [PATCH 75/79] fix drf save --- radio/radio_save_raw/radio_save_raw.grc | 49 ++++++++-- .../radio_save_raw/radio_save_raw.py | 91 +++++++++---------- 2 files changed, 85 insertions(+), 55 deletions(-) diff --git a/radio/radio_save_raw/radio_save_raw.grc b/radio/radio_save_raw/radio_save_raw.grc index 1648de42..400809b8 100644 --- a/radio/radio_save_raw/radio_save_raw.grc +++ b/radio/radio_save_raw/radio_save_raw.grc @@ -1,6 +1,7 @@ options: parameters: author: '' + catch_exceptions: 'True' category: '[GRC Hier Blocks]' cmake_opt: '' comment: '' @@ -49,17 +50,48 @@ blocks: coordinate: [11, 203] rotation: 0 state: true -- name: gr_digital_rf_digital_rf_channel_sink_0 - id: gr_digital_rf_digital_rf_channel_sink +- name: gr_digital_rf_digital_rf_sink_0 + id: gr_digital_rf_digital_rf_sink parameters: affinity: '' alias: '' center_freqs: '[]' + channel0: ch0 + channel1: ch1 + channel10: ch10 + channel11: ch11 + channel12: ch12 + channel13: ch13 + channel14: ch14 + channel15: ch15 + channel16: ch16 + channel17: ch17 + channel18: ch18 + channel19: ch19 + channel2: ch2 + channel20: ch20 + channel21: ch21 + channel22: ch22 + channel23: ch23 + channel24: ch24 + channel25: ch25 + channel26: ch26 + channel27: ch27 + channel28: ch28 + channel29: ch29 + channel3: ch3 + channel30: ch30 + channel31: ch31 + channel4: ch4 + channel5: ch5 + channel6: ch6 + channel7: ch7 + channel8: ch8 + channel9: ch9 checksum: 'False' comment: '' compression_level: '0' debug: 'False' - dir: directory_name file_cadence_ms: '1000' ignore_tags: 'False' input: fc32 @@ -67,21 +99,23 @@ blocks: marching_periods: 'True' metadata: '{}' min_chunksize: '0' + nchan: '1' sample_rate_denominator: '1' sample_rate_numerator: int(samp_rate) start: '''now''' stop_on_skipped: 'False' stop_on_time_tag: 'False' subdir_cadence_s: '3600' + top_level_dir: directory_name uuid: '' vlen: '1' states: bus_sink: false bus_source: false bus_structure: null - coordinate: [659, 110] + coordinate: [656, 108.0] rotation: 0 - state: true + state: enabled - name: samp_rate id: parameter parameters: @@ -105,8 +139,10 @@ blocks: address: tcp://127.0.0.1:5558 affinity: '' alias: '' + bind: 'False' comment: '' hwm: '-1' + key: '' maxoutbuf: '0' minoutbuf: '0' pass_tags: 'True' @@ -122,7 +158,8 @@ blocks: state: true connections: -- [zeromq_sub_source_0, '0', gr_digital_rf_digital_rf_channel_sink_0, '0'] +- [zeromq_sub_source_0, '0', gr_digital_rf_digital_rf_sink_0, '0'] metadata: file_format: 1 + grc_version: 3.10.9.2 diff --git a/srt/daemon/radio_control/radio_save_raw/radio_save_raw.py b/srt/daemon/radio_control/radio_save_raw/radio_save_raw.py index cf1c1ad7..6867306f 100644 --- a/srt/daemon/radio_control/radio_save_raw/radio_save_raw.py +++ b/srt/daemon/radio_control/radio_save_raw/radio_save_raw.py @@ -21,8 +21,9 @@ class radio_save_raw(gr.top_block): + def __init__(self, directory_name="./rf_data", samp_rate=2400000): - gr.top_block.__init__(self, "radio_save_raw") + gr.top_block.__init__(self, "radio_save_raw", catch_exceptions=True) ################################################## # Parameters @@ -33,42 +34,43 @@ def __init__(self, directory_name="./rf_data", samp_rate=2400000): ################################################## # Blocks ################################################## - self.zeromq_sub_source_0 = zeromq.sub_source( - gr.sizeof_gr_complex, 1, "tcp://127.0.0.1:5558", 100, True, -1 - ) - self.gr_digital_rf_digital_rf_channel_sink_0 = ( - gr_digital_rf.digital_rf_channel_sink( - channel_dir=directory_name, - dtype=np.complex64, - subdir_cadence_secs=3600, - file_cadence_millisecs=1000, - sample_rate_numerator=int(samp_rate), - sample_rate_denominator=1, - start="now", - ignore_tags=False, - is_complex=True, - num_subchannels=1, - uuid_str=None, - center_frequencies=[], - metadata={}, - is_continuous=True, - compression_level=0, - checksum=False, - marching_periods=True, - stop_on_skipped=False, - stop_on_time_tag=False, - debug=False, - min_chunksize=None, - ) + + self.zeromq_sub_source_0 = zeromq.sub_source(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', False) + self.gr_digital_rf_digital_rf_sink_0 = gr_digital_rf.digital_rf_sink( + directory_name, + channels=[ + 'ch0', + ], + dtype=np.complex64, + subdir_cadence_secs=3600, + file_cadence_millisecs=1000, + sample_rate_numerator=int(samp_rate), + sample_rate_denominator=1, + start='now', + ignore_tags=False, + is_complex=True, + num_subchannels=1, + uuid_str=None, + center_frequencies=( + None + ), + metadata={}, + is_continuous=True, + compression_level=0, + checksum=False, + marching_periods=True, + stop_on_skipped=False, + stop_on_time_tag=False, + debug=False, + min_chunksize=None, ) + ################################################## # Connections ################################################## - self.connect( - (self.zeromq_sub_source_0, 0), - (self.gr_digital_rf_digital_rf_channel_sink_0, 0), - ) + self.connect((self.zeromq_sub_source_0, 0), (self.gr_digital_rf_digital_rf_sink_0, 0)) + def get_directory_name(self): return self.directory_name @@ -83,31 +85,22 @@ def set_samp_rate(self, samp_rate): self.samp_rate = samp_rate + def argument_parser(): parser = ArgumentParser() parser.add_argument( - "--directory-name", - dest="directory_name", - type=str, - default="./rf_data", - help="Set ./rf_data [default=%(default)r]", - ) + "--directory-name", dest="directory_name", type=str, default="./rf_data", + help="Set ./rf_data [default=%(default)r]") parser.add_argument( - "--samp-rate", - dest="samp_rate", - type=intx, - default=2400000, - help="Set samp_rate [default=%(default)r]", - ) + "--samp-rate", dest="samp_rate", type=intx, default=2400000, + help="Set samp_rate [default=%(default)r]") return parser def main(top_block_cls=radio_save_raw, options=None): if options is None: options = argument_parser().parse_args() - tb = top_block_cls( - directory_name=options.directory_name, samp_rate=options.samp_rate - ) + tb = top_block_cls(directory_name=options.directory_name, samp_rate=options.samp_rate) def sig_handler(sig=None, frame=None): tb.stop() @@ -123,5 +116,5 @@ def sig_handler(sig=None, frame=None): tb.wait() -if __name__ == "__main__": - main() +if __name__ == '__main__': + main() \ No newline at end of file From 0dbe360e64e8641aa983275908ba4ce235bf23dc Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Mon, 25 Nov 2024 15:34:01 -0500 Subject: [PATCH 76/79] config ghange to make the maximum elevation of the antenna 87 degrees instead of 85 --- config/config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/config.yaml b/config/config.yaml index a4ddb392..3dcd82eb 100644 --- a/config/config.yaml +++ b/config/config.yaml @@ -12,7 +12,7 @@ AZLIMITS: upper_bound: 360.0 ELLIMITS: lower_bound: 0.0 - upper_bound: 85.0 + upper_bound: 87.0 STOW_LOCATION: azimuth: 60.0 elevation: 30.0 From 19e6be05df6b2378a83e997138b7bbd44afe9a5a Mon Sep 17 00:00:00 2001 From: JLab Account on Scotty Server Date: Wed, 27 Nov 2024 20:44:15 +0000 Subject: [PATCH 77/79] fix oddball extra ZMQ command that seems to break the radio control on computers other than scotty --- .../radio_control/radio_process/radio_process.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 9dde2b20..a8cc2b4e 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -76,12 +76,12 @@ def __init__(self, num_bins=256, num_integrations=100000): # Blocks ################################################## - self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True, True) - self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True, True) - self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True, True) - self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True, True) - self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True, True) - self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True, True) + self.zeromq_pub_sink_2_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5561', 100, False, (-1), '', True) + self.zeromq_pub_sink_2 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5560', 100, True, (-1), '', True) + self.zeromq_pub_sink_1_0 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5562', 100, True, (-1), '', True) + self.zeromq_pub_sink_1 = zeromq.pub_sink(gr.sizeof_float, num_bins, 'tcp://127.0.0.1:5563', 100, False, (-1), '', True) + self.zeromq_pub_sink_0_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5559', 100, False, (-1), '', True) + self.zeromq_pub_sink_0 = zeromq.pub_sink(gr.sizeof_gr_complex, 1, 'tcp://127.0.0.1:5558', 100, True, (-1), '', True) self.xmlrpc_server_0 = SimpleXMLRPCServer(('localhost', 5557), allow_none=True) self.xmlrpc_server_0.register_instance(self) self.xmlrpc_server_0_thread = threading.Thread(target=self.xmlrpc_server_0.serve_forever) From 246161973a363874cef83fd00744e1b554699367 Mon Sep 17 00:00:00 2001 From: dsheen2019 <49729918+dsheen2019@users.noreply.github.com> Date: Tue, 25 Feb 2025 14:34:07 -0500 Subject: [PATCH 78/79] rotor compatibility fixes for normal SRTs (#13) modded config to lose extra params for the rotors and put them back in the code that defines the rotators for now --- srt/daemon/daemon.py | 48 +++++++++++-------- .../radio_process/radio_process.py | 8 ++-- srt/daemon/rotor_control/motors.py | 5 +- srt/daemon/rotor_control/rotors.py | 15 +++++- 4 files changed, 50 insertions(+), 26 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index 282cf5c3..c540b0ab 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -31,7 +31,7 @@ #pull astropy things into the daemon too for now so we can create skycoord objects here more easily -from astropy.coordinates import SkyCoord, EarthLocation, get_sun, get_moon +from astropy.coordinates import SkyCoord, EarthLocation from astropy.coordinates import ICRS, Galactic, FK4, CIRS, AltAz, LSR from astropy.utils.iers.iers import conf from astropy.table import Table @@ -84,9 +84,11 @@ def __init__(self, config_directory, config_dict): (point["azimuth"], point["elevation"]) for point in config_dict["HORIZON_POINTS"] ] + self.motor_type = config_dict["MOTOR_TYPE"] self.motor_port = config_dict["MOTOR_PORT"] self.motor_baudrate = config_dict["MOTOR_BAUDRATE"] + self.radio_center_frequency = config_dict["RADIO_CF"] self.radio_sample_frequency = config_dict["RADIO_SF"] self.radio_rf_gain = config_dict["RADIO_RF_GAIN"] @@ -143,8 +145,13 @@ def __init__(self, config_directory, config_dict): self.az_limits, self.el_limits, ) + + #vars pulled in from rotor definition + #self.rotor.rotor_loop_cadence + #self.rotor.pointing_accuracy + print("test", self.stow_location) - self.rotor_location = self.stow_location + self.rotor_location = (0,0)#self.stow_location self.rotor_destination = self.stow_location self.rotor_offsets = (0.0, 0.0) self.rotor_cmd_location = tuple( @@ -303,7 +310,7 @@ def point_at_object(self, object_id): self.ephemeris_cmd_location = object_id self.rotor_destination = new_rotor_cmd_location self.rotor_cmd_location = new_rotor_cmd_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + while not azel_within_range(self.rotor_location, self.rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): sleep(0.1) else: self.log_message(f"Object {object_id} Not in Motor Bounds") @@ -344,7 +351,7 @@ def point_at_azel(self, az, el): if self.rotor.angles_within_bounds(*new_rotor_cmd_location): self.rotor_destination = new_rotor_destination self.rotor_cmd_location = new_rotor_cmd_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + while not azel_within_range(self.rotor_location, self.rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): self.rotor_destination = new_rotor_destination self.rotor_cmd_location = new_rotor_cmd_location sleep(0.1) @@ -400,7 +407,7 @@ def point_at_galactic(self, l_pos, b_pos): self.ephemeris_cmd_location = object_id self.rotor_destination = new_rotor_cmd_location self.rotor_cmd_location = new_rotor_cmd_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + while not azel_within_range(self.rotor_location, self.rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): sleep(0.1) else: self.log_message(f"Object {object_id} Not in Motor Bounds") @@ -443,7 +450,7 @@ def point_at_radec(self, ra_pos, dec_pos): self.ephemeris_cmd_location = object_id self.rotor_destination = new_rotor_cmd_location self.rotor_cmd_location = new_rotor_cmd_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + while not azel_within_range(self.rotor_location, self.rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): sleep(0.1) else: self.log_message(f"Object {object_id} Not in Motor Bounds") @@ -470,7 +477,7 @@ def point_at_offset(self, az_off, el_off): if self.rotor.angles_within_bounds(*new_rotor_cmd_location): self.rotor_offsets = new_rotor_offsets self.rotor_cmd_location = new_rotor_cmd_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + while not azel_within_range(self.rotor_location, self.rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): sleep(0.1) else: self.log_message(f"Offset {new_rotor_offsets} Out of Bounds") @@ -530,7 +537,7 @@ def calibrate(self): #start saving new calibration file sleep(0.1+2*self.radio_num_bins * self.radio_integ_cycles / self.radio_sample_frequency) - self.start_recording(name=cold_sky_name, file_dir=self.config_dir) + self.start_recording(name=cold_sky_name, file_dir=self.config_directory) sleep((self.cal_cycles+1)*self.radio_num_bins* self.radio_integ_cycles/ self.radio_sample_frequency) self.stop_recording() @@ -823,7 +830,7 @@ def find_object_location(self, name): self.ephemeris_cmd_location = name self.rotor_destination = new_rotor_cmd_location self.rotor_cmd_location = new_rotor_cmd_location - while not azel_within_range(self.rotor_location, self.rotor_cmd_location): + while not azel_within_range(self.rotor_location, self.rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): sleep(0.1) else: self.log_message(f"Object {name} Not in Motor Bounds") @@ -907,18 +914,20 @@ def update_rotor_status(self): last_time = time() while True: + try: current_rotor_cmd_location = self.rotor_cmd_location if not azel_within_range( - self.rotor_location, current_rotor_cmd_location): - + self.rotor_location, current_rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy)): + self.rotor.set_azimuth_elevation( *current_rotor_cmd_location) - sleep(0.1) + + sleep(self.rotor.rotor_loop_cadence) start_time = time() while ( not azel_within_range( - self.rotor_location, current_rotor_cmd_location + self.rotor_location, current_rotor_cmd_location, bounds=(self.rotor.pointing_accuracy,self.rotor.pointing_accuracy) ) ) and (time() - start_time) < 15: past_rotor_location = self.rotor_location @@ -941,15 +950,13 @@ def update_rotor_status(self): self.current_vlsr = self.ephemeris_tracker.calculate_vlsr(sky_coord,obstime) self.radio_queue.put(("vlsr", float(self.current_vlsr))) - sleep(0.1) + sleep(self.rotor.rotor_loop_cadence) else: - #past_rotor_location = self.rotor_location - #self.rotor_location = self.rotor.get_azimuth_elevation() - if (time() - last_time) > 5 : #don't bother recomputing the celestial coordinates so often if we're not actally moving + self.rotor.set_azimuth_elevation(*current_rotor_cmd_location) #always reissue pointing commands periodically and let rotor decide whether to adjust - sleep(0.1) + #sleep(0.3) #move this to the pointing routine in motors.py where it belongs past_rotor_location = self.rotor_location self.rotor_location = self.rotor.get_azimuth_elevation() @@ -970,8 +977,9 @@ def update_rotor_status(self): self.radio_queue.put(("vlsr", float(self.current_vlsr))) last_time = time() + print(f'last_time = {last_time}') - sleep(0.1) #make it much more responsive to commands + sleep(self.rotor.rotor_loop_cadence) #make it much more responsive to commands #aparrently making this loop too fast causes stability issues. prolly need to tweak rotor level code a bit to not #crash and burn ir a read comes in before it has a status update request comes before it has new data @@ -1086,7 +1094,7 @@ def srt_daemon_main(self): self.radio_process_task.start() except RuntimeError as e: self.log_message(str(e)) - sleep(5) #wait a bit for the radio to actually start up + sleep(10) #wait a bit for the radio to actually start up # Send Settings to the GNU Radio Script radio_params = { diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index a8cc2b4e..9a531247 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -103,8 +103,8 @@ def __init__(self, num_bins=256, num_integrations=100000): ) self.uhd_usrp_source_1.set_samp_rate(samp_rate) - self.uhd_usrp_source_1.set_clock_source("external") - self.uhd_usrp_source_1.set_time_source("external") + self.uhd_usrp_source_1.set_clock_source("internal") + self.uhd_usrp_source_1.set_time_source("internal") _last_pps_time = self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() # Poll get_time_last_pps() every 50 ms until a change is seen while(self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() == _last_pps_time): @@ -114,12 +114,14 @@ def __init__(self, num_bins=256, num_integrations=100000): # Sleep 1 second to ensure next PPS has come time.sleep(1) - self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) + #self.uhd_usrp_source_1.set_center_freq(rf_freq, 0) + self.uhd_usrp_source_1.set_center_freq(uhd.tune_request(self.rf_freq,self.samp_rate*0.6), 0) #offset tune self.uhd_usrp_source_1.set_antenna("RX2", 0) self.uhd_usrp_source_1.set_bandwidth(samp_rate, 0) self.uhd_usrp_source_1.set_gain(rf_gain, 0) self.uhd_usrp_source_1.set_auto_dc_offset(True, 0) + ##### Manually Configure USRP GPIO self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'CTRL', 0x000, 0xFFF ^ calibrator_mask) #set pins 2 and 3 manual self.uhd_usrp_source_1.set_gpio_attr('FP0A', 'DDR', 0xFFF, calibrator_mask) #set pins 2 and 3 as output diff --git a/srt/daemon/rotor_control/motors.py b/srt/daemon/rotor_control/motors.py index 36491b26..2fd5ccca 100644 --- a/srt/daemon/rotor_control/motors.py +++ b/srt/daemon/rotor_control/motors.py @@ -296,6 +296,7 @@ def point(self, az, el): az_relative = az - self.az_limits[0] el_relative = el - self.el_limits[0] self.send_rot2_pkt(cmd, az=az_relative, el=el_relative) + sleep(0.3) def status(self): """Requests the Current Location of the ROT2 Motor @@ -784,6 +785,7 @@ def point(self, az, el): None """ self.send_pushrod_cmd(az, el, 0) + sleep(0.5) def status(self): """Requests the Current Location of the Pushrod Motor @@ -823,7 +825,8 @@ def point(self, az, el): None """ self.client.goto_posvel_azel(az, el, 0.0, 0.0) - self.position = (az, el) + sleep(0.01) + #self.position = (az, el) def status(self): """Returns the Position of the Dish diff --git a/srt/daemon/rotor_control/rotors.py b/srt/daemon/rotor_control/rotors.py index 669ed69b..8839acf8 100644 --- a/srt/daemon/rotor_control/rotors.py +++ b/srt/daemon/rotor_control/rotors.py @@ -7,7 +7,6 @@ from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor, W1XMBigDishMotor - def angle_within_range(angle, limits): lower_limit, upper_limit = limits if lower_limit <= upper_limit: @@ -38,7 +37,8 @@ class Rotor: """ def __init__(self, motor_type, port, baudrate, az_limits, el_limits): - """Initializes the Rotor with its Motor Object + """Initializes the Rotor with its Motor Object and defines + fixed parameters needed for control and settling checks Parameters ---------- @@ -51,16 +51,27 @@ def __init__(self, motor_type, port, baudrate, az_limits, el_limits): el_limits : (float, float) Tuple of Lower and Upper Elevation Limits """ + if motor_type == RotorType.NONE or motor_type == RotorType.NONE.value: self.motor = NoMotor(port, baudrate, az_limits, el_limits) + self.rotor_loop_cadence = 0.5 + self.pointing_accuracy = 1.0 elif motor_type == RotorType.ROT2 or motor_type == RotorType.ROT2.value: self.motor = Rot2Motor(port, baudrate, az_limits, el_limits) + self.rotor_loop_cadence = 0.5 + self.pointing_accuracy = 0.6 elif motor_type == RotorType.H180 or motor_type == RotorType.H180.value: self.motor = H180Motor(port, baudrate, az_limits, el_limits) + self.rotor_loop_cadence = 0.5 + self.pointing_accuracy = 0.6 elif motor_type == RotorType.PUSH_ROD == RotorType.PUSH_ROD.value: self.motor = PushRodMotor(port, baudrate, az_limits, el_limits) + self.rotor_loop_cadence = 0.5 + self.pointing_accuracy = 0.6 elif motor_type == RotorType.W1XM_BIG_DISH or motor_type == RotorType.W1XM_BIG_DISH.value: self.motor = W1XMBigDishMotor() + self.rotor_loop_cadence = 0.1 + self.pointing_accuracy = 0.1 else: raise ValueError("Not a known motor type") From 4b2008c5d4759d431b6c93bba0c2abf17ee5548a Mon Sep 17 00:00:00 2001 From: Daniel Sheen Date: Tue, 25 Feb 2025 14:52:40 -0500 Subject: [PATCH 79/79] fix a couple haystack specific things that got left in by accident --- srt/daemon/daemon.py | 1 - srt/daemon/radio_control/radio_process/radio_process.py | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py index c540b0ab..6e899f60 100644 --- a/srt/daemon/daemon.py +++ b/srt/daemon/daemon.py @@ -977,7 +977,6 @@ def update_rotor_status(self): self.radio_queue.put(("vlsr", float(self.current_vlsr))) last_time = time() - print(f'last_time = {last_time}') sleep(self.rotor.rotor_loop_cadence) #make it much more responsive to commands #aparrently making this loop too fast causes stability issues. prolly need to tweak rotor level code a bit to not diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py index 9a531247..22f9c384 100755 --- a/srt/daemon/radio_control/radio_process/radio_process.py +++ b/srt/daemon/radio_control/radio_process/radio_process.py @@ -103,8 +103,8 @@ def __init__(self, num_bins=256, num_integrations=100000): ) self.uhd_usrp_source_1.set_samp_rate(samp_rate) - self.uhd_usrp_source_1.set_clock_source("internal") - self.uhd_usrp_source_1.set_time_source("internal") + self.uhd_usrp_source_1.set_clock_source("external") + self.uhd_usrp_source_1.set_time_source("external") _last_pps_time = self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() # Poll get_time_last_pps() every 50 ms until a change is seen while(self.uhd_usrp_source_1.get_time_last_pps().get_real_secs() == _last_pps_time):