diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index 086d7c3e..451d9016 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -2,9 +2,78 @@
srt-py Change Log
=================
-.. current developments
-vv1.1.1
+**Current developments:**
+
+**Added:**
+
+* ``DASHBOARD_THREADS``, ``NPOINT_INTEG_TIME``, ``MINIMAL_ARROWS_DISTANCE``, ``PLAY_SOUNDS``, ``NPOINT_ARROWS``, ``SPECTRUM_HISTORY_LENGTH``, ``WATERFALL_LENGTH``, ``GUI_TIMEZONE``, ``DISPLAY_LIM``, ``DRAW_ECLIPTIC``, ``DRAW_EQUATOR``, ``N_PNT_COUNT``, ``BSWITCH_INTEG_TIME``, ``GOTO_STOW_AT_STARTUP`` parameters
+* CASSI motor support
+* Baudrate check for H180 and CASSI motors classes
+* Non-physical limit warning
+* Windrose letters and lines in Azimuth and Elevation Graph
+* Buttons to modebar: all shape drawing, ``togglespikelines`` and ``togglehover``
+* Drawing of n-point scan points on az-el graph
+* Drawing arrows showing motor route
+* ``playsound`` command
+* Optional sound when n-point scan and beam switch are complete
+* ``rot_curve.txt`` command file
+* ``ocl-icd-system`` to the recipe to avoid https://github.com/MITHaystack/srt-py/issues/21#issuecomment-1963827916
+* ``tzlocal`` to recipe
+* Optional arrows showing route of n-point scan
+* ``azel_to_coords.py``, ``coords_to_azel.py``
+* Recording indicator to system page
+* Waterfall spectrum plot
+* Spectrum history length to parameter
+* User now can choose timezone in Monitor Page
+* Az-el graph display limits to parameter
+* Optional drawing of ecliptic and equator planes
+* Real size Sun and Moon shapes
+* Logging messages to beam switch
+* Warning message when angle out of bounds during n-point scan and beam switch
+* Log message at the end of n-point scan and beam switch
+* Beam switch graph
+* Option to automatically go to STOW at startup
+
+**Changed:**
+
+* Remember zoom after refresh in Azimuth and Elevation Graph
+* Hide Plotly logo
+* Enabe scroll zoom
+* ``monitor_page.png``
+* fk4 to icrs in ``sky_coords.csv``
+* Sort the system page by newest issue first
+* Different marker types on az el graph
+* Marker for visability to circular
+* Number of n-point scan rotor positions to parameter
+* Height of n-point scan graph to 300
+* N-point scan and beam switch integration times to parameters
+
+**Fixed:**
+
+* Searching for default config dir (https://github.com/MITHaystack/srt-py/issues/23)
+* Astropy deprecations
+* H180 class: init (https://github.com/MITHaystack/srt-py/issues/21) and updating ``self.az_count``, ``self.el_count`` (https://github.com/MITHaystack/srt-py/issues/24)
+* N-point scan and beam switch numbering (off-by-one error)
+* Conda build error (https://github.com/MITHaystack/srt-py/issues/19)
+* N-point scan and beam switch center not updated during scan (https://github.com/MITHaystack/srt-py/issues/25)
+* Visability rectangle for negative STOW azimuth (overwritten by: marker for visability to circular)
+* Dash deprecation: ``className`` to ``class_name`` (https://github.com/AlexKurek/srt-py/commit/43946aa7e8453154096ddc45c092f506cda00cff)
+* ``utcfromtimestamp`` deprecation
+* Comment unused modules in ``srt/daemon/radio_control/`` (https://github.com/AlexKurek/srt-py/commit/9a3f9d05a5b0fd2e2b8300441605010e2586599c)
+* Graphs appear faster
+* Beam switch count (off-by-one error)
+
+**Known issues:**
+
+* A lot of waitress logging messages is printed (https://github.com/MITHaystack/srt-py/issues/27)
+* Beam-switch and N-Point Scan not possible after Direct Point to the same object (https://github.com/MITHaystack/srt-py/issues/29)
+* Versioneer is outdated and not supporting current Python versions
+* GOTO_STOW_AT_STARTUP not working
+
+
+
+v1.1.1
====================
**Added:**
@@ -14,7 +83,7 @@ vv1.1.1
-vv1.1.0
+v1.1.0
====================
**Added:**
diff --git a/README.md b/README.md
index cbcc5e94..a8d52744 100644
--- a/README.md
+++ b/README.md
@@ -20,18 +20,80 @@ This software is written in pure Python, and so depends on having an installed v
### Building the Conda Package Locally
-After downloading the srt-py source repository, open up a command prompt or terminal with conda installed and navigate to the folder containing the srt-py directory. Additionally, ensure that you have conda-build and conda-verify installed
+Download srt-py source repository using command prompt or terminal with conda installed:
+```
+conda update -y --all
+git clone https://github.com/AlexKurek/srt-py
+```
+
+Ensure that you have `conda-build` and `conda-verify` installed
+
+```
+conda install -y conda-build conda-verify
+```
+
+Build the conda package
+
+```
+conda build -c conda-forge srt-py --no-test --no-anaconda-upload
+```
+
+Create a new conda env, switch it to the conda-forge channel and activate it
```
-conda install conda-build conda-verify
+conda create -y -n srtpy
+conda activate srtpy
+conda config --env --add channels conda-forge
+conda config --env --set channel_priority strict
```
-Build and install the conda package
+Install the package
```
-conda-build srt-py
-conda install -c file://${CONDA_PREFIX}/conda-bld/ srt-py
+conda install -y --use-local srt-py
+```
+
+Copy config files and an exemplary command file to your HOME:
+
+```
+mkdir ~/.srtpy-config/
+cp -r ~/srt-py/config/{config.yaml,schema.yaml,sky_coords.csv} ~/.srtpy-config/
+cp ~/srt-py/examples/example_cmd_file.txt ~/
+rm -rf ~/srt-py/
+```
+
+Enable udev device setup of rtl-sdr hardware
+
```
+sudo ln -s ~/miniconda3/envs/srtpy/lib/udev/rules.d/rtl-sdr.rules /etc/udev/rules.d/
+```
+
+Reload your udev rules
+
+```
+sudo udevadm control --reload && sudo udevadm trigger
+```
+
+Cleanup
+
+```
+conda deactivate
+conda build purge
+```
+
+If you have Ubuntu 22 and getting https://askubuntu.com/questions/1403705/dev-ttyusb0-not-present-in-ubuntu-22-04
+
+```
+sudo apt purge brltty
+sudo rm -rv /var/lib/BrlAPI/
+```
+
+If you are getting `Cannot open /dev/ttyUSB0: Permission denied`
+```
+sudo usermod -a -G tty,dialout $USER
+```
+
+Do a proper logout or reboot.
### Building the Pip Package Locally (Not Recommended due to Dependency Issues)
@@ -104,14 +166,14 @@ The bar at the top of the dashboard manages sending commands to the SRT, which a
Additionally, there are four different interactive graphs displayed on this screen.
The 'Power vs Time' graph displays the received power over a certain range of time into the past.
-The first of the two spectrum graphs, 'Raw Spectrum', shows the processed and integrated radio FFT data, whose values don't necessarily have any real world units and have a shape that is influenced by the band-pass filter. The other, 'Calibrated Spectrum' shows the values after dividing out the calibration values taken when the 'Calibrate' command was last run on a test source of known temperature (such as a clump of trees or a noise diode).
-Finally, there is the Azimuth-Elevation graph, which shows the current position of all objects specified to be tracked in the sky_coords.csv configuration file, as well as the reachable limits of the motor and the horizon. Clicking on a point allows you to send a command to track that object, perform an n-point scan about the object, or repeatedly move the antenna across it.
+The first of the two spectrum graphs, 'Raw Spectrum', shows the processed and integrated radio FFT data, whose values don't necessarily have any real world units and have a shape that is influenced by the band-pass filter. The other, 'Calibrated Spectrum', shows the values after dividing out the calibration values taken when the 'Calibrate' command was last run on a test source of known temperature (such as a clump of trees or a noise diode). 'Raw Spectrum History' shows a waterfall plot sometimes called also a dynamic spectrum.
+Finally, there is the Azimuth-Elevation graph, which shows the current position of all objects specified to be tracked in the sky_coords.csv configuration file, as well as the reachable limits of the motor and the horizon. Clicking on a point allows you to send a command to track that object, perform an n-point scan about the object, or repeatedly move the antenna across it.
#### System Page UI

-The System Page contains many displays of information not necessary for actively controlling the SRT. In case of a serious problem occuring when operating the SRT, there is a section for Emergency Contact Info. There is similarly a 'Message Logs' scrolling area for logs sent from the SRT, in order to assist in debugging or just determining what it has done recently. In the middle is a more verbose status blurb about the status of the SRT's command queue, including the number of commands queued up and what the SRT is currently trying to run. Finally, there is also a list of the files and folders in the SRT's specified recording save directory, which users can directly download files from via the dashboard if the "DASHBOARD_DOWNLOADS" setting in the configuration YAML is set to Yes.
+The System Page contains many displays of information not necessary for actively controlling the SRT. In case of a serious problem occuring when operating the SRT, there is a section for Emergency Contact Info. There is similarly a 'Message Logs' scrolling area for logs sent from the SRT, in order to assist in debugging or just determining what it has done recently. In the middle is a more verbose status blurb about the status of the SRT's command queue, including the number of commands queued up and what the SRT is currently trying to run. Finally, there is also a list of the files and folders in the SRT's specified recording save directory, which users can directly download files from via the dashboard if the "DASHBOARD_DOWNLOADS" setting in the configuration YAML is set to Yes.
### Running Headless / Command Line Usage
@@ -164,6 +226,8 @@ srt_controller.py status --status_parameter=motor_azel
- plotly
- pandas
- waitress
+- ocl-icd-system
+- tzlocal
## Accommodating Different Hardware
@@ -187,9 +251,10 @@ Adding a new antenna motor therefore requires:
- Making the string name for that motor create that motor in [rotors.py](srt/daemon/rotor_control/rotors.py)
- Adding the string name as an valid option in the [YAML schema](config/schema.yaml) MOTOR_TYPE so the new type will be considered valid, such as:
```
-MOTOR_TYPE: enum('ALFASPID', 'H180MOUNT', 'PUSHROD', 'NONE')
+MOTOR_TYPE: enum('ALFASPID', 'H180MOUNT', 'PUSHROD', 'NONE', 'CASSI')
```
- Changing the MOTOR_TYPE in your own configuration YAML to the new motor type
+- Adding the string name to the condition in `generate_az_el_graph` method in [graphs.py](https://github.com/AlexKurek/srt-py/blob/master/srt/dashboard/layouts/graphs.py).
## Further Documentation
diff --git a/bin/srt_runner.py b/bin/srt_runner.py
old mode 100644
new mode 100755
index dbff1a33..136efe71
--- a/bin/srt_runner.py
+++ b/bin/srt_runner.py
@@ -11,6 +11,7 @@
from waitress import serve
from srt import config_loader
+from os.path import expanduser
def run_srt_daemon(configuration_dir, configuration_dict):
@@ -28,6 +29,7 @@ def run_srt_dashboard(configuration_dir, configuration_dict):
app_server,
host=configuration_dict["DASHBOARD_HOST"],
port=configuration_dict["DASHBOARD_PORT"],
+ threads=configuration_dict["DASHBOARD_THREADS"],
)
@@ -41,7 +43,7 @@ def run_srt_dashboard(configuration_dir, configuration_dict):
metavar="config_dir",
type=str,
help="The Path to the SRT Config Directory",
- default="~/.srt-config",
+ default=expanduser("~/.srt-config"),
)
my_parser.add_argument(
"--config_file_name",
@@ -50,13 +52,11 @@ def run_srt_dashboard(configuration_dir, configuration_dict):
help="The filename of the Config File to Load",
default="config.yaml",
)
-
my_parser.add_argument(
"--dash_only",
dest="dash_only",
action="store_true",
help="Load up the dashboard only",
-
)
# Execute the parse_args() method
args = my_parser.parse_args()
diff --git a/config/config.yaml b/config/config.yaml
index 68b33910..09e69398 100644
--- a/config/config.yaml
+++ b/config/config.yaml
@@ -41,8 +41,26 @@ BEAMWIDTH: 7.0
TSYS: 171
TCAL: 290
SAVE_DIRECTORY: ~/Desktop/SRT-Saves
+NPOINT_INTEG_TIME: 5.0
+BSWITCH_INTEG_TIME: 5.0
+MINIMAL_ARROWS_DISTANCE: 5.0
RUN_HEADLESS: No
DASHBOARD_PORT: 8080
DASHBOARD_HOST: 0.0.0.0
DASHBOARD_DOWNLOADS: Yes
DASHBOARD_REFRESH_MS: 3000
+DASHBOARD_THREADS: 8
+PLAY_SOUNDS: Yes
+NPOINT_ARROWS: Yes
+SPECTRUM_HISTORY_LENGTH: 1000
+WATERFALL_LENGTH: 200
+GUI_TIMEZONE: UTC
+DISPLAY_LIM:
+ az_lower_display_lim: 0
+ az_upper_display_lim: 360
+ el_lower_display_lim: 0
+ el_upper_display_lim: 90
+DRAW_ECLIPTIC: Yes
+DRAW_EQUATOR: Yes
+N_PNT_COUNT: 25
+GOTO_STOW_AT_STARTUP: Yes
diff --git a/config/schema.yaml b/config/schema.yaml
index b781f3a6..94f4ff9f 100644
--- a/config/schema.yaml
+++ b/config/schema.yaml
@@ -5,7 +5,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', 'CASSI')
MOTOR_BAUDRATE: int()
MOTOR_PORT: str()
RADIO_CF: int()
@@ -19,11 +19,25 @@ BEAMWIDTH: num()
TSYS: num()
TCAL: num()
SAVE_DIRECTORY: str()
+NPOINT_INTEG_TIME: num()
+BSWITCH_INTEG_TIME: num()
+MINIMAL_ARROWS_DISTANCE: num()
RUN_HEADLESS: bool()
DASHBOARD_PORT: int()
DASHBOARD_HOST: ip()
DASHBOARD_DOWNLOADS: bool()
DASHBOARD_REFRESH_MS: int()
+DASHBOARD_THREADS: int()
+PLAY_SOUNDS: bool()
+NPOINT_ARROWS: bool()
+SPECTRUM_HISTORY_LENGTH: int()
+WATERFALL_LENGTH: int()
+GUI_TIMEZONE: str()
+DISPLAY_LIM: include('disp_limit')
+DRAW_ECLIPTIC: bool()
+DRAW_EQUATOR: bool()
+N_PNT_COUNT: int()
+GOTO_STOW_AT_STARTUP: bool()
---
location:
latitude: num()
@@ -42,3 +56,8 @@ contact_info:
name: str()
email: str()
phone_number: str()
+disp_limit:
+ az_lower_display_lim: num()
+ az_upper_display_lim: num()
+ el_lower_display_lim: num()
+ el_upper_display_lim: num()
diff --git a/config/sky_coords.csv b/config/sky_coords.csv
index 7c7a7d5e..c3ec64e9 100644
--- a/config/sky_coords.csv
+++ b/config/sky_coords.csv
@@ -1,53 +1,53 @@
-coordinate_system,coordinate_a,coordinate_b,name
-fk4,05 31 30,21 58 00,Crab
-fk4,05 32 48,-5 27 00,Orion
-fk4,05 42 00,-1 00 00,S8
-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,21 12 00,48 00 00,G90
-fk4,05 40 00,29 00 00,G180
-fk4,12 48 00,28 00 00,GNpole
-fk4,00 39 00,40 30 00,Androm
-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,10,0,G10
-galactic,20,0,G20
-galactic,30,0,G30
-galactic,40,0,G40
-galactic,50,0,G50
-galactic,60,0,G60
-galactic,70,0,G70
-galactic,80,0,G80
-galactic,90,0,G90
-galactic,100,0,G100
-galactic,110,0,G110
-galactic,120,0,G120
-galactic,130,0,G130
-galactic,140,0,G140
-galactic,150,0,G150
-galactic,160,0,G160
-galactic,170,0,G170
-galactic,180,0,G180
-galactic,190,0,G190
-galactic,200,0,G200
-galactic,210,0,G210
-galactic,220,0,G220
-galactic,230,0,G230
-galactic,240,0,G240
-galactic,250,0,G250
-galactic,260,0,G260
-galactic,270,0,G270
-galactic,280,0,G280
-galactic,290,0,G290
-galactic,300,0,G300
-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
+coordinate_system, coordinate_a, coordinate_b, name
+icrs, 05 34 31, 22 00 53, Crab
+icrs, 05 35 17, -5 23 24, Orion
+icrs, 05 44 33, -0 58 47, S8
+icrs, 23 23 28, 59 00 28, Cass
+icrs, 17 46 04, -28 51 08, SgrA
+icrs, 06 31 51, 04 54 47, Rosett
+icrs, 18 20 23, -16 16 37, M17
+icrs, 20 28 47, 41 10 03, CygEMN
+icrs, 21 13 44, 48 12 27, G90
+icrs, 05 43 11, 29 01 20, G180
+icrs, 12 50 26, 27 43 41, GNpole
+icrs, 00 41 44, 40 46 27, Androm
+icrs, 05 17 08, 18 47 13, AC1
+icrs, 03 32 47, 54 10 07, PULSAR
+icrs, 08 31 41, -45 10 13, PS
+galactic, 10,1, RC_CLOUD
+galactic, 00,0, G00
+galactic, 10,0, G10
+galactic, 20,0, G20
+galactic, 30,0, G30
+galactic, 40,0, G40
+galactic, 50,0, G50
+galactic, 60,0, G60
+galactic, 70,0, G70
+galactic, 80,0, G80
+galactic, 90,0, G90
+galactic, 100,0, G100
+galactic, 110,0, G110
+galactic, 120,0, G120
+galactic, 130,0, G130
+galactic, 140,0, G140
+galactic, 150,0, G150
+galactic, 160,0, G160
+galactic, 170,0, G170
+galactic, 180,0, G180
+galactic, 190,0, G190
+galactic, 200,0, G200
+galactic, 210,0, G210
+galactic, 220,0, G220
+galactic, 230,0, G230
+galactic, 240,0, G240
+galactic, 250,0, G250
+galactic, 260,0, G260
+galactic, 270,0, G270
+galactic, 280,0, G280
+galactic, 290,0, G290
+galactic, 300,0, G300
+galactic, 310,0, G310
+galactic, 320,0, G320
+galactic, 330,0, G330
+galactic, 340,0, G340
+galactic, 350,0, G350
diff --git a/docs/command_files.md b/docs/command_files.md
index a0b02a7e..fca9e893 100644
--- a/docs/command_files.md
+++ b/docs/command_files.md
@@ -5,24 +5,25 @@ Note: The SRT 2020 software uses a command syntax heavily influenced by the comm
The SRT software accepts commands in order to change settings at runtime as well as control the running operations. All commands are funneled into a command queue, which will execute them in order of being received. Parameters for a command should be separated by spaces. Most commands are not case sensitive and do not care about excess whitespace.
-| Command | Parameters | Notes |Info |
-|--------------|------------|-------|--------------------------------------------|
-| * | Any text | 1 | Makes Line a Comment |
-| stow | None | | Sends the Antenna to Stow |
-| cal | None | | Sends the Antenna to Calibration Position |
-| calibrate | None | 2 | Saves Current Spec as Calibration Data |
-| quit | None | 3 | Stows and Gracefully Closes Daemon |
-| 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' |
-| 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 |
-| [name] | [n] or [b] | 5 | Points Antenna at Object named 'name' |
+| Command | Parameters | Notes |Info |
+|--------------|------------|-------|-------------------------------------------------|
+| * | Any text | 1 | Makes Line a Comment |
+| stow | None | | Sends the Antenna to Stow |
+| cal | None | | Sends the Antenna to Calibration Position |
+| calibrate | None | 2 | Saves Current Spec as Calibration Data |
+| quit | None | 3 | Stows and Gracefully Closes Daemon |
+| 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' |
+| wait | [time] | | Stops Execution and Waits for 'time' Secs. |
+| playsound | [string] | | Uses Ubuntu's Speech Dispatcher to declaim text |
+| [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 |
+| [name] | [n] or [b] | 5 | Points Antenna at Object named 'name' |
Additional Notes:
1. Only is considered a comment if the line starts with '\*'.
diff --git a/docs/config_directory.md b/docs/config_directory.md
index 1bc01ad7..698c2171 100644
--- a/docs/config_directory.md
+++ b/docs/config_directory.md
@@ -3,20 +3,20 @@
The configuration folder for the SRT contains all of the important settings that allow the SRT to operate in different modes and with different default values. This is split across several different files, including:
- * 'config.yaml' - The main configuration file for the SRT, containing all of the key settings
- * 'sky_coords.csv' - A CSV file listing all celestial objects that the user would like to be able to track automatically
+ * `config.yaml` - The main configuration file for the SRT, containing all of the key settings
+ * `sky_coords.csv` - A CSV file listing all celestial objects that the user would like to be able to track automatically
As well as the below, which the user should not typically have to modify:
- * 'schema.yaml' - The schema for config.yaml, which lists the valid range of options in config.yaml
- * 'calibration.json' - A JSON containing the calibration data from the most recent time the calibrate command was running
+ * `schema.yaml` - The schema for config.yaml, which lists the valid range of options in `config.yaml`
+ * `calibration.json` - A JSON containing the calibration data from the most recent time the calibrate command was running
-If the user wants to add configuration options within these files they must update schema.yaml and config.yaml and make sure they are in the same directory together when calling srt_runner.py.
+If the user wants to add configuration options within these files they must update `schema.yaml` and `config.yaml` and make sure they are in the same directory together when calling `srt_runner.py`.
##### config.yaml
-The config.yaml file contains the following settings:
+The `config.yaml` file contains the following settings:
-* STATION - The latitude, longitude, and name of the location of the SRT.
+* STATION - The latitude, longitude, and name of the location of the SRT. Note that the convention differs from SRT Java and C versions, where e.g. Eastern Europe had a negative longitude, whereas now it should be positive.
```YAML
STATION:
latitude: 42.5
@@ -60,42 +60,42 @@ CAL_LOCATION:
elevation: 7.0
```
-* MOTOR_TYPE - The type of motor being used. Several different types are currently allowed, include NONE (which works for either a fixed antenna or simulating on a system without an antenna), ALFASPID (which works with any ROT2 protocol supporting motor), H180MOUNT (which works with the H180 motor on some SRTs), and PUSHROD (which works with the old custom pushrod system of the SRT). Currently, since the SRT at Haystack uses a ALFASPID motor, that is the only one which has currently been extensively tested. Additionally, please refer to the in-code documentation in srt/daemon/rotor_control for more information on adding support for more motors.
+* MOTOR_TYPE - The type of motor being used. Several different types are currently allowed, include NONE (which works for either a fixed antenna or simulating on a system without an antenna), ALFASPID (which works with any ROT2 protocol supporting motor), H180MOUNT (which works with the Kaul-Tronics Inc. H180 motor on some SRTs), CASSI (which works with the CASSI Corp. mount) and PUSHROD (which works with the old custom pushrod system of the SRT). Currently, since the SRT at Haystack uses a ALFASPID motor, that is the only one which has currently been extensively tested. Additionally, please refer to the in-code documentation in `srt/daemon/rotor_control/` for more information on adding support for more motors. See also https://ui.adsabs.harvard.edu/abs/2005AAS...20717301C/abstract.
```YAML
MOTOR_TYPE: NONE
```
-* MOTOR_PORT - The location of the motor on the host system. For example, on a Unix system this will probably be some device like '/dev/ttyUSB0', on Mac is will be something like '/dev/tty.usbserial-A602P777' and on Windows this will be a COM port like 'COM3'. This is not used if MOTOR_TYPE is NONE.
+* MOTOR_PORT - The location of the motor on the host system. For example, on a Unix system this will probably be some device like `/dev/ttyUSB0`, on Mac is will be something like `/dev/tty.usbserial-A602P777` and on Windows this will be a COM port like `COM3`. This is not used if MOTOR_TYPE is NONE.
```YAML
MOTOR_PORT: /dev/ttyUSB0
```
-* MOTOR_BAUDRATE - The baudrate for the serial connection to the motor controller. The ALFASPID motor baudrate can vary depending on the specific model, the ROT2PROG is 600, while the MD-01/MD-02 default setting is 460800. This can be changed and see the instruction manual to learn how to set and check this value. The H180MOUNT is 2400 and the PUSHROD is 2000. This is not used if MOTOR_TYPE is NONE.
+* MOTOR_BAUDRATE - The baudrate for the serial connection to the motor controller. The ALFASPID motor baudrate can vary depending on the specific model, the ROT2PROG is 600, while the MD-01/MD-02 default setting is 460800. This can be changed and see the instruction manual to learn how to set and check this value. The H180MOUNT and CASSI is 2400 and the PUSHROD is 2000. This is not used if MOTOR_TYPE is NONE.
```YAML
MOTOR_BAUDRATE: 600
```
-* RADIO_CF - The default center frequency of the SRT in Hz. The center frequency of the SRT can be changed during run-time, but this is the default and initial value on startup.
+* RADIO_CF - The default center frequency of the SRT in Hz. The center frequency of the SRT can be changed during run-time, but this is the default and initial value on startup.
```YAML
RADIO_CF: 1420000000
```
-* RADIO_SF - The sample frequency of the SRT in Hz. Since SDRs typically take both an I and Q sample at this rate, the sample frequency is conveniently also the effective bandwidth. This can be changed during run-time, but this is the default and initial value on startup.
+* RADIO_SF - The sample frequency of the SRT in Hz. Since SDRs typically take both an I and Q sample at this rate, the sample frequency is conveniently also the effective bandwidth. This can be changed during run-time, but this is the default and initial value on startup.
```YAML
RADIO_SF: 2000000
```
-* RADIO_NUM_BINS - The number of bins that the FFT will output. More bins means a more precise spectrum, but at a higher computational cost.
+* RADIO_NUM_BINS - The number of bins that the FFT will output. More bins means a more precise spectrum, but at a higher computational cost.
```YAML
RADIO_NUM_BINS: 4096
```
-* RADIO_INTEG_CYCLES - The number of FFT output arrays to average over before saving or displaying the result. Higher values means a more accurate spectrum, but less frequently updating. Note that the integration time can be calculated using RADIO_NUM_BINS * RADIO_INTEG_CYCLES / RADIO_SF.
+* RADIO_INTEG_CYCLES - The number of FFT output arrays to average over before saving or displaying the result. Higher values means a more accurate spectrum, but less frequently updating. Note that the integration time can be calculated using RADIO_NUM_BINS * RADIO_INTEG_CYCLES / RADIO_SF.
```YAML
RADIO_INTEG_CYCLES: 1000
```
-* RADIO_AUTOSTART - Whether to automatically start the GNU Radio script that performs the FFT and integration when the program starts. Keep this True for default behavior, but if a custom radio processing script is desired, make this false and run your own following the input and outputs used in radio/radio_processing to make sure all the data gets to the right places
+* RADIO_AUTOSTART - Whether to automatically start the GNU Radio script that performs the FFT and integration when the program starts. Keep this True for default behavior, but if a custom radio processing script is desired, make this false and run your own following the input and outputs used in `radio/radio_processing/` to make sure all the data gets to the right places
```YAML
RADIO_AUTOSTART: Yes
```
@@ -120,20 +120,94 @@ TCAL: 290
SAVE_DIRECTORY: ~/Desktop/SRT-Saves
```
+* NPOINT_INTEG_TIME - The integration time in seconds at each point of an n-point scan. In the case of the Cassi mount, this should not be less than 4s.
+```YAML
+NPOINT_INTEG_TIME: 5.0
+```
+
+* BSWITCH_INTEG_TIME - The integration time in seconds at each point of a beam switch. In the case of the Cassi mount, this should not be less than 4s.
+```YAML
+BSWITCH_INTEG_TIME: 5.0
+
+* MINIMAL_ARROWS_DISTANCE - The minimum Euclidean distance in degrees between the current motor position and the coordinates of the object to be moved to. If it is not exceeded, the arrows representing the movement of the telescope will not be displayed.
+```YAML
+MINIMAL_ARROWS_DISTANCE: 5.0
+```
+
* DASHBOARD_REFRESH_MS - The number of milliseconds for dashboard refresh.
```YAML
DASHBOARD_REFRESH_MS: 3000
```
+
+* DASHBOARD_THREADS - The number of threads for dash. 8 seems to be enought at the host. If also a client is connected and you are getting `WARNING:waitress.queue:Task queue depth is 1`, consider increasing this value.
+```YAML
+DASHBOARD_THREADS: 8
+```
+
+* PLAY_SOUNDS - Whether to use Ubuntu's [speech dispatcher](https://manpages.ubuntu.com/manpages/trusty/man1/speech-dispatcher.1.html) to say when the N-point scan and beam switch are finished.
+```YAML
+PLAY_SOUNDS: Yes
+```
+
+* N_PNT_COUNT - How many rotor positions during the n-point scan. This number must be a square of a natural number >1. The recommended value is 25.
+```YAML
+N_PNT_COUNT: 25
+```
+
+* NPOINT_ARROWS - Whether to display arrows showing the motor route during n-point scanning.
+```YAML
+NPOINT_ARROWS: Yes
+```
+
+* SPECTRUM_HISTORY_LENGTH - How many spectra to keep in history (memory).
+```YAML
+SPECTRUM_HISTORY_LENGTH: 1000
+```
+
+* WATERFALL_LENGTH - How many spectra to display on Waterfall Plot.
+```YAML
+WATERFALL_LENGTH: 200
+```
+
+* GUI_TIMEZONE - Whether to display axes on charts in `UTC` or `local` time.
+```YAML
+GUI_TIMEZONE: UTC
+```
+
+* DISPLAY_LIM - Display limits at az-el graph
+```YAML
+DISPLAY_LIM:
+ az_lower_display_lim: 0
+ az_upper_display_lim: 360
+ el_lower_display_lim: 0
+ el_upper_display_lim: 90
+```
+
+* DRAW_ECLIPTIC - Whether to draw ecliptic plane.
+```YAML
+DRAW_ECLIPTIC: Yes
+```
+
+* DRAW_EQUATOR - Whether to draw equator plane.
+```YAML
+DRAW_EQUATOR: Yes
+```
+
+* GOTO_STOW_AT_STARTUP - Whether to go to STOW at startup.
+```YAML
+GOTO_STOW_AT_STARTUP: Yes
+```
+
##### sky_coords.csv
The sky_coords data file is organized into four columns, with a row for each entry.
-* The first column is the coordinate system of the celestial object, which supports any coordinate system name recognized by AstroPy, and has been tested with 'fk4' and 'galactic'.
+* The first column is the coordinate system of the celestial object, which supports any coordinate system name [recognized by AstroPy](https://docs.astropy.org/en/stable/coordinates/index.html#built-in-frame-classes), and has been tested with `fk4` and `galactic`.
* The next two columns are the first and second coordinate of the object, such as ra and dec for fk4 and l and b for galactic.
* The last column is the name of the object.
-All points listed here will show up as points on the Dashboard, and the SRT will be able to track their movements. Additionally, their names will become keywords in command files, so to point at a object given the name Orion, the command would just be 'Orion'.
+All points listed here will show up as points on the Dashboard, and the SRT will be able to track their movements. Additionally, their names will become keywords in command files, so to point at a object given the name Orion, the command would just be `Orion`.
-Below is an example excerpt of a sky_coords.csv file:
+Below is an example excerpt of a `sky_coords.csv` file:
```CSV
coordinate_system,coordinate_a,coordinate_b,name
fk4,05 31 30,21 58 00,Crab
diff --git a/docs/images/monitor_page.png b/docs/images/monitor_page.png
index 0befb573..0548c635 100644
Binary files a/docs/images/monitor_page.png and b/docs/images/monitor_page.png differ
diff --git a/examples/example_cmd_file.txt b/examples/example_cmd_file.txt
index bca9c4a2..5a2acf8d 100644
--- a/examples/example_cmd_file.txt
+++ b/examples/example_cmd_file.txt
@@ -5,3 +5,4 @@ record
wait 50
roff
stow
+playsound All commands completed
diff --git a/examples/rot_curve.txt b/examples/rot_curve.txt
new file mode 100644
index 00000000..eac3d68c
--- /dev/null
+++ b/examples/rot_curve.txt
@@ -0,0 +1,42 @@
+G00
+record g00.fits
+250
+roff
+G10
+record g10.fits
+250
+roff
+G20
+record g20.fits
+250
+roff
+G30
+record g30.fits
+250
+roff
+G40
+record g40.fits
+250
+roff
+G50
+record g50.fits
+250
+roff
+G60
+record g60.fits
+250
+roff
+G70
+record g70.fits
+250
+roff
+G80
+record g80.fits
+250
+roff
+G90
+record g90.fits
+250
+roff
+playsound Observations completed
+stow
diff --git a/recipe/bld.bat b/recipe/bld.bat
deleted file mode 100644
index c40a9bbe..00000000
--- a/recipe/bld.bat
+++ /dev/null
@@ -1,2 +0,0 @@
-"%PYTHON%" setup.py install
-if errorlevel 1 exit 1
diff --git a/recipe/build.sh b/recipe/build.sh
deleted file mode 100644
index 971b5b98..00000000
--- a/recipe/build.sh
+++ /dev/null
@@ -1 +0,0 @@
-$PYTHON setup.py install # Python command to install the script.
diff --git a/recipe/meta.yaml b/recipe/meta.yaml
index ea410b74..9d7f8a02 100644
--- a/recipe/meta.yaml
+++ b/recipe/meta.yaml
@@ -1,43 +1,55 @@
-{% set name = "srt-py" %}
-{% set version = "0.0.0" %}
+{% set version = "1.1.1" %}
package:
- name: "{{ name|lower }}"
+ name: "srt-py"
version: "{{ version }}"
source:
path: ../
+build:
+ noarch: python
+ number: 0
+ script: {{ PYTHON }} -m pip install . -vv
+
requirements:
host:
- pip
- - setuptools
- python >=3.6
+ - setuptools
run:
- - python >=3.6
- - numpy
- - scipy
- - rtl-sdr
- - soapysdr
- - soapysdr-module-rtlsdr
- - gnuradio-core
- - gnuradio-zeromq
- - gnuradio-osmosdr
- - digital_rf
- - pyzmq
- - pyserial
- astropy
- - yamale
- dash
- dash-bootstrap-components
- dash-html-components
- dash-core-components
- - plotly
+ - digital_rf
+ - gnuradio-core
+ - gnuradio-zeromq
+ - gnuradio-osmosdr
- pandas
+ - plotly
+ - pyserial
+ - python >=3.6
+ - pyzmq
+ - numpy
+ - rtl-sdr
+ - scipy
+ - soapysdr
+ - soapysdr-module-rtlsdr
- waitress
+ - yamale
+ - ocl-icd-system # https://github.com/MITHaystack/srt-py/issues/21#issuecomment-1963827916
+ - tzlocal
test:
requires:
- pytest
imports:
- srt
+
+about:
+ home: https://github.com/MITHaystack/srt-py
+ summary: Small Radio Telescope Control Code for Python
+ license: MIT
+ license_file: license
diff --git a/rever.xsh b/rever.xsh
index 89f0b071..a032096e 100644
--- a/rever.xsh
+++ b/rever.xsh
@@ -13,9 +13,11 @@ $ACTIVITIES = [
]
+$TAG_TEMPLATE = 'v$VERSION'
$VERSION_BUMP_PATTERNS = [ # These note where/how to find the version numbers
('srt/__init__.py', r'__version__\s*=.*', "__version__ = '$VERSION'"),
- ('setup.py', r'version\s*=.*,', "version='$VERSION',")
+ ('setup.py', r'version\s*=.*,', "version='$VERSION',"),
+ ('recipe/meta.yaml', r'{%\s*set\s*version\s*=.*', '{% set version = "$VERSION" %}')
]
$CHANGELOG_FILENAME = 'CHANGELOG.rst' # Filename for the changelog
$CHANGELOG_TEMPLATE = 'TEMPLATE.rst' # Filename for the news template
diff --git a/scripts/test_ephemeris.py b/scripts/test_ephemeris.py
index 6d85f017..5d2e76e8 100644
--- a/scripts/test_ephemeris.py
+++ b/scripts/test_ephemeris.py
@@ -3,6 +3,7 @@
Calculates and Displays All AzEl Coordinates Above the Horizon
"""
+
from srt.daemon.utilities.object_tracker import EphemerisTracker
import matplotlib.pyplot as plt
diff --git a/scripts/test_motor.py b/scripts/test_motor.py
index 017622c4..c01fcdbd 100644
--- a/scripts/test_motor.py
+++ b/scripts/test_motor.py
@@ -3,6 +3,7 @@
Moves a Motor Through 10 Random Points and Back to Stow
"""
+
from random import uniform
from time import sleep
diff --git a/scripts/test_yaml.py b/scripts/test_yaml.py
index af666234..73f89c56 100644
--- a/scripts/test_yaml.py
+++ b/scripts/test_yaml.py
@@ -3,6 +3,7 @@
Validates and Prints the YAML Dictionary
"""
+
from srt.daemon.utilities.yaml_tools import validate_yaml_schema, load_yaml
if __name__ == "__main__":
diff --git a/scripts/verify_coords/azel_to_coords.py b/scripts/verify_coords/azel_to_coords.py
new file mode 100755
index 00000000..d9a830b4
--- /dev/null
+++ b/scripts/verify_coords/azel_to_coords.py
@@ -0,0 +1,39 @@
+#!/usr/bin/env python
+"""azel_to_coords.py
+
+Calculates Coords from Az, El. Helps to create test objects for sky_coords.csv.
+
+"""
+import astropy.units as u
+from astropy.coordinates import EarthLocation, SkyCoord
+from astropy.time import Time
+from pytz import timezone
+
+if __name__ == "__main__":
+ location = EarthLocation(
+ lat=50.0465664 * u.deg, lon=19.8279168 * u.deg, height=313 * u.m
+ )
+
+ # custom time
+ # utcoffset = +2*u.hour
+ # time = Time('2024-4-19 12:41:00') - utcoffset
+
+ # current time
+ tz = timezone("Europe/Warsaw")
+ time = Time.now()
+ time = time.to_datetime(timezone=tz)
+
+ coords = SkyCoord(
+ 20, 20, frame="altaz", unit="deg", obstime=time, location=location
+ )
+ icrs = coords.transform_to("icrs")
+
+ az = icrs.ra
+ el = icrs.dec
+
+ ra = az.to_string(unit=u.hour, sep=" ", precision=0)
+ dec = el.to_string(unit=u.deg, sep=" ", precision=0)
+
+ print(f"Coords = {coords}")
+ print(f"ra = {ra}")
+ print(f"dec = {dec}")
diff --git a/scripts/verify_coords/coords_to_azel.py b/scripts/verify_coords/coords_to_azel.py
new file mode 100755
index 00000000..6f6a8427
--- /dev/null
+++ b/scripts/verify_coords/coords_to_azel.py
@@ -0,0 +1,35 @@
+#!/usr/bin/env python
+"""coords_to_azel.py
+
+Calculates Az and El from Coords. Inverse of azel_to_coords.py.
+
+"""
+import astropy.units as u
+from astropy.coordinates import AltAz, EarthLocation, SkyCoord
+from astropy.time import Time
+from pytz import timezone
+
+
+if __name__ == "__main__":
+
+ object_str = "Orion Nebula"
+ object = SkyCoord.from_name(object_str)
+
+ location = EarthLocation(
+ lat=50.0465664 * u.deg, lon=19.8279168 * u.deg, height=313 * u.m
+ )
+
+ # custom time
+ # utcoffset = +2*u.hour
+ # time = Time('2024-4-19 12:41:00') - utcoffset
+
+ # current time
+ tz = timezone("Europe/Warsaw")
+ time = Time.now()
+ time = time.to_datetime(timezone=tz)
+
+ altaz = object.transform_to(AltAz(obstime=time, location=location))
+
+ print(f"Object: {object_str}")
+ print(f"Altitude = {altaz.alt}")
+ print(f"Longtitude = {altaz.az}")
diff --git a/setup.py b/setup.py
index 2c32607d..33b073c2 100644
--- a/setup.py
+++ b/setup.py
@@ -10,7 +10,7 @@
setuptools.setup(
name="srt-py",
- version='v1.1.1',
+ version="v1.1.1",
include_package_data=True,
cmdclass=versioneer.get_cmdclass(),
author="MIT Haystack",
diff --git a/srt/__init__.py b/srt/__init__.py
index 98de0bf1..4ab79714 100644
--- a/srt/__init__.py
+++ b/srt/__init__.py
@@ -1,3 +1,3 @@
from . import _version
-__version__ = 'v1.1.1'
+__version__ = "v1.1.1"
diff --git a/srt/config_loader.py b/srt/config_loader.py
index fbf64b93..ff1be931 100644
--- a/srt/config_loader.py
+++ b/srt/config_loader.py
@@ -3,6 +3,7 @@
Module Containing Brief Functions for Validating and Parsing YAML
"""
+
import yamale
import yaml
diff --git a/srt/daemon/daemon.py b/srt/daemon/daemon.py
index 530211cd..c321841b 100644
--- a/srt/daemon/daemon.py
+++ b/srt/daemon/daemon.py
@@ -5,7 +5,7 @@
"""
from time import sleep, time
-from datetime import timedelta, datetime
+from datetime import timedelta, datetime, timezone
from threading import Thread
from queue import Queue
from xmlrpc.client import ServerProxy
@@ -25,7 +25,10 @@
RadioSaveSpecFitsTask,
)
from .utilities.object_tracker import EphemerisTracker
-from .utilities.functions import azel_within_range, get_spectrum
+from .utilities.functions import azel_within_range, get_spectrum, is_square
+
+import subprocess
+from math import sqrt, ceil
class SmallRadioTelescopeDaemon:
@@ -52,10 +55,18 @@ def __init__(self, config_directory, config_dict):
config_dict["AZLIMITS"]["lower_bound"],
config_dict["AZLIMITS"]["upper_bound"],
)
+ if abs(self.az_limits[0] - self.az_limits[1]) > 360:
+ print(
+ "Distance between AZLIMITS is greater than 360 deg. Consider lowering the upper limit."
+ )
self.el_limits = (
config_dict["ELLIMITS"]["lower_bound"],
config_dict["ELLIMITS"]["upper_bound"],
)
+ if abs(self.el_limits[0] - self.el_limits[1]) > 90:
+ print(
+ "Distance between ELLIMITS is greater than 90 deg. Consider lowering the upper limit."
+ )
self.stow_location = (
config_dict["STOW_LOCATION"]["azimuth"],
config_dict["STOW_LOCATION"]["elevation"],
@@ -82,6 +93,30 @@ 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.npoint_integration_time = config_dict["NPOINT_INTEG_TIME"]
+ self.bswitch_integration_time = config_dict["BSWITCH_INTEG_TIME"]
+ self.minimal_arrows_distance = config_dict["MINIMAL_ARROWS_DISTANCE"]
+ self.play_sounds = config_dict["PLAY_SOUNDS"]
+ self.npoint_arrows = config_dict["NPOINT_ARROWS"]
+ self.waterfall_length = config_dict["WATERFALL_LENGTH"]
+ self.gui_timezone = config_dict["GUI_TIMEZONE"]
+ if self.gui_timezone != "UTC" and self.gui_timezone != "local":
+ print(
+ "Unknows value of GUI_TIMEZONE: '"
+ + self.gui_timezone
+ + "'. It has to be 'UTC' or 'local'. Defaulting to UTC."
+ )
+ self.gui_timezone = "UTC"
+ self.display_lim = (
+ config_dict["DISPLAY_LIM"]["az_lower_display_lim"],
+ config_dict["DISPLAY_LIM"]["az_upper_display_lim"],
+ config_dict["DISPLAY_LIM"]["el_lower_display_lim"],
+ config_dict["DISPLAY_LIM"]["el_upper_display_lim"],
+ )
+ self.draw_ecliptic = config_dict["DRAW_ECLIPTIC"]
+ self.draw_equator = config_dict["DRAW_EQUATOR"]
+ self.n_pnt_count = config_dict["N_PNT_COUNT"]
+ self.goto_stow_at_startup = config_dict["GOTO_STOW_AT_STARTUP"]
# Generate Default Calibration Values
# Values are Set Up so that Uncalibrated and Calibrated Spectra are the Same Values
@@ -119,7 +154,7 @@ def __init__(self, config_directory, config_dict):
self.az_limits,
self.el_limits,
)
- self.rotor_location = self.stow_location
+ self.rotor_location = self.stow_location # this may not always be true at startup
self.rotor_destination = self.stow_location
self.rotor_offsets = (0.0, 0.0)
self.rotor_cmd_location = tuple(
@@ -142,6 +177,8 @@ def __init__(self, config_directory, config_dict):
# List for data that will be plotted in the app
self.n_point_data = []
self.beam_switch_data = []
+ self.rotor_loc_npoint_live = []
+ self.power_bswitch_live = []
def log_message(self, message):
"""Writes Contents to a Logging List and Prints
@@ -155,11 +192,11 @@ def log_message(self, message):
-------
None
"""
- self.command_error_logs.append((time(), message))
+ self.command_error_logs.insert(0, (time(), message))
print(message)
- def n_point_scan(self, object_id):
- """Runs an N-Point (25) Scan About an Object
+ def n_point_scan(self, n_pnt_count, object_id):
+ """Runs an N-Point Scan About an Object
Parameters
----------
@@ -170,49 +207,79 @@ def n_point_scan(self, object_id):
-------
None
"""
+ if n_pnt_count < 4:
+ print("The value of N_PNT_COUNT is <4. Scan may not work.")
+ if is_square(n_pnt_count) == False:
+ print(
+ "The value of N_PNT_COUNT is not a square of a natural number. Scan may not work."
+ )
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
- N_pnt_default = 25
rotor_loc = []
pwr_list = []
- #
- 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))
- i = (scan // 5) - 2
- j = (scan % 5) - 2
+ scan_center_list = []
+ np_sides = [sqrt(n_pnt_count), sqrt(n_pnt_count)]
+ for scan in range(n_pnt_count):
+ current_scan_center = self.ephemeris_locations[object_id]
+ scan_center_list.append(current_scan_center)
+ self.log_message("{0} of {1} point scan.".format(scan + 1, n_pnt_count))
+ i = (scan // sqrt(n_pnt_count)) - 2
+ j = (scan % sqrt(n_pnt_count)) - 2
el_dif = i * self.beamwidth * 0.5
- az_dif_scalar = np.cos((scan_center[1] + el_dif) * np.pi / 180.0)
+ az_dif_scalar = np.cos((current_scan_center[1] + el_dif) * np.pi / 180.0)
# Avoid issues where you get close to the zenith
- if np.abs(az_dif_scalar)<1e-4:
+ if np.abs(az_dif_scalar) < 1e-4:
az_dif = 0
else:
az_dif = j * self.beamwidth * 0.5 / az_dif_scalar
-
+
new_rotor_offsets = (az_dif, el_dif)
- if self.rotor.angles_within_bounds(*scan_center):
- self.rotor_destination = scan_center
+ if self.rotor.angles_within_bounds(*current_scan_center):
+ self.rotor_destination = current_scan_center
self.point_at_offset(*new_rotor_offsets)
+ else:
+ print(
+ """Angle not within bounds, skipping iteration. Scan results will be biased.
+ It is recommended to run another scan further away from the bounds."""
+ )
rotor_loc.append(self.rotor_location)
- sleep(5)
+ self.rotor_loc_npoint_live = rotor_loc
+ sleep(self.npoint_integration_time)
raw_spec = get_spectrum(port=5561)
p = np.sum(raw_spec)
a = len(raw_spec)
pwr = (self.temp_sys + self.temp_cal) * p / (a * self.cal_power)
pwr_list.append(pwr)
+ self.log_message("N-point scan has finished.")
maxdiff = (az_dif, el_dif)
+
+ sc_az = [t[0] for t in scan_center_list]
+ sc_el = [t[1] for t in scan_center_list]
+ sc_az_mean = sum(sc_az) / len(sc_az)
+ sc_el_mean = sum(sc_el) / len(sc_el)
+ scan_center = (sc_az_mean, sc_el_mean)
+
self.n_point_data = [scan_center, maxdiff, rotor_loc, pwr_list, np_sides]
# add code to collect spectrum data.
self.rotor_offsets = (0.0, 0.0)
self.ephemeris_cmd_location = object_id
+ if self.play_sounds == True:
+ try:
+ subprocess.call(["speech-dispatcher"], stdout=subprocess.DEVNULL)
+ subprocess.call(["spd-say", '"N-point scan has finished"'])
+ except:
+ print(
+ """Sounds are enabled in the config file, but there was a problem and could not play sound.
+ (The playback mechanism uses Ubuntu's speech dispatcher)."""
+ )
+
def beam_switch(self, object_id):
"""Swings Antenna Across Object
@@ -231,10 +298,23 @@ def beam_switch(self, object_id):
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 = []
- for j in range(0, 3 * self.num_beamswitches):
+ for j in range(0, (3 * self.num_beamswitches) - 1):
+ new_rotor_destination = self.ephemeris_locations[object_id]
+ if (j == 0) or ((j + 1) % 3 == 0):
+ if j == 0:
+ self.log_message(
+ "{0} of {1} beam switch.".format(
+ ceil((j + 1) / 3), self.num_beamswitches
+ )
+ )
+ else:
+ self.log_message(
+ "{0} of {1} beam switch.".format(
+ ceil((j + 1) / 3) + 1, self.num_beamswitches
+ )
+ )
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
@@ -242,18 +322,35 @@ def beam_switch(self, object_id):
if self.rotor.angles_within_bounds(*new_rotor_destination):
self.rotor_destination = new_rotor_destination
self.point_at_offset(*new_rotor_offsets)
+ else:
+ print(
+ """Angle not within bounds, skipping iteration. Results will be biased.
+ It is recommended to repeat the run further away from the boundaries."""
+ )
rotor_loc.append(self.rotor_location)
- sleep(5)
+ sleep(self.bswitch_integration_time)
raw_spec = get_spectrum(port=5561)
p = np.sum(raw_spec)
a = len(raw_spec)
pwr = (self.temp_sys + self.temp_cal) * p / (a * self.cal_power)
pwr_list.append(pwr)
+ self.power_bswitch_live = pwr_list
+ self.log_message("Beam switch has finished.")
self.rotor_offsets = (0.0, 0.0)
self.radio_queue.put(("beam_switch", 0))
self.ephemeris_cmd_location = object_id
self.beam_switch_data = [rotor_loc, pwr_list]
+ if self.play_sounds == True:
+ try:
+ subprocess.call(["speech-dispatcher"], stdout=subprocess.DEVNULL)
+ subprocess.call(["spd-say", '"Beam switch has finished"'])
+ except:
+ print(
+ """Sounds are enabled in the config file, but there was a problem and could not play sound.
+ (The playback mechanism uses Ubuntu's speech dispatcher)."""
+ )
+
def point_at_object(self, object_id):
"""Points Antenna Directly at Object, and Sets Up Tracking to Follow it
@@ -483,6 +580,30 @@ def quit(self):
self.keep_running = False
self.radio_queue.put(("is_running", self.keep_running))
+ def play_sound(self, command):
+ """Declaims a text
+
+ Parameters
+ ----------
+ command : string
+ Text to declaim
+
+ Returns
+ -------
+ None
+ """
+ if self.play_sounds == True:
+ command = command.replace("playsound ", "")
+ command = '"' + command + '"'
+ try:
+ subprocess.call(["speech-dispatcher"], stdout=subprocess.DEVNULL)
+ subprocess.call(["spd-say", command])
+ except:
+ print(
+ """Sounds are enabled in the config file, but there was a problem and could not play sound.
+ (The playback mechanism uses Ubuntu's speech dispatcher)."""
+ )
+
def update_ephemeris_location(self):
"""Periodically Updates Object Locations for Tracking Sky Objects
@@ -619,7 +740,20 @@ def update_status(self):
"temp_sys": self.temp_sys,
"cal_power": self.cal_power,
"n_point_data": self.n_point_data,
+ "rotor_loc_npoint_live": self.rotor_loc_npoint_live,
+ "power_bswitch_live": self.power_bswitch_live,
"beam_switch_data": self.beam_switch_data,
+ "num_beamswitches": self.num_beamswitches,
+ "minimal_arrows_distance": self.minimal_arrows_distance,
+ "npoint_arrows": self.npoint_arrows,
+ "motor_type": self.motor_type,
+ "radio_save_task": str(self.radio_save_task),
+ "waterfall_length": self.waterfall_length,
+ "gui_timezone": self.gui_timezone,
+ "display_lim": self.display_lim,
+ "station": self.station,
+ "draw_ecliptic": self.draw_ecliptic,
+ "draw_equator": self.draw_equator,
"time": time(),
}
status_socket.send_json(status)
@@ -718,11 +852,19 @@ def srt_daemon_main(self):
status_thread.start()
radio_thread.start()
+ if self.goto_stow_at_startup == True:
+ self.log_message("GOTO_STOW_AT_STARTUP option is on; running command 'stow'")
+ self.stow()
+ else:
+ self.log_message("GOTO_STOW_AT_STARTUP option is off; not going to STOW")
while self.keep_running:
try:
# Await Command for the SRT
self.current_queue_item = "None"
command = self.command_queue.get()
+ # Make n-point scan markers disappear on next command
+ if command != "None":
+ self.rotor_loc_npoint_live = []
self.log_message(f"Running Command '{command}'")
self.current_queue_item = command
if len(command) < 2 or command[0] == "*":
@@ -736,7 +878,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(self.n_pnt_count, object_id=command_parts[0])
elif command_parts[-1] == "b": # Beam-Switch Away From Object
self.beam_switch(object_id=command_parts[0])
else: # Point Directly At Object
@@ -749,6 +891,8 @@ def srt_daemon_main(self):
self.calibrate()
elif command_name == "quit":
self.quit()
+ elif command_name == "playsound":
+ self.play_sound(command=command)
elif command_name == "record":
self.start_recording(
name=(None if len(command_parts) <= 1 else command_parts[1])
@@ -777,16 +921,16 @@ def srt_daemon_main(self):
elif command_name.split(":")[0] == "lst": # Wait Until Next Time H:M:S
time_string = command_name.replace("LST:", "")
time_val = datetime.strptime(time_string, "%H:%M:%S")
- while time_val < datetime.utcfromtimestamp(time()):
+ while time_val < datetime.fromtimestamp(time(), timezone.utc):
time_val += timedelta(days=1)
time_delta = (
- time_val - datetime.utcfromtimestamp(time())
+ time_val - datetime.fromtimestamp(time(), timezone.utc)
).total_seconds()
sleep(time_delta)
elif len(command_name.split(":")) == 5: # Wait Until Y:D:H:M:S
time_val = datetime.strptime(command_name, "%Y:%j:%H:%M:%S")
time_delta = (
- time_val - datetime.utcfromtimestamp(time())
+ time_val - datetime.fromtimestamp(time(), timezone.utc)
).total_seconds()
sleep(time_delta)
else:
diff --git a/srt/daemon/radio_control/radio_calibrate/radio_calibrate.py b/srt/daemon/radio_control/radio_calibrate/radio_calibrate.py
index 8f59130f..5f4781c2 100644
--- a/srt/daemon/radio_control/radio_calibrate/radio_calibrate.py
+++ b/srt/daemon/radio_control/radio_calibrate/radio_calibrate.py
@@ -9,12 +9,13 @@
# GNU Radio version: 3.8.1.0
from gnuradio import gr
-from gnuradio.filter import firdes
+# from gnuradio.filter import firdes
import sys
import signal
from argparse import ArgumentParser
-from gnuradio.eng_arg import eng_float, intx
-from gnuradio import eng_notation
+# from gnuradio.eng_arg import eng_float, intx
+from gnuradio.eng_arg import intx
+# from gnuradio import eng_notation
from gnuradio import zeromq
from . import save_calibration
diff --git a/srt/daemon/radio_control/radio_calibrate/save_calibration.py b/srt/daemon/radio_control/radio_calibrate/save_calibration.py
index 00a40f3e..e800705d 100644
--- a/srt/daemon/radio_control/radio_calibrate/save_calibration.py
+++ b/srt/daemon/radio_control/radio_calibrate/save_calibration.py
@@ -11,7 +11,7 @@
import json
from gnuradio import gr
-import pmt
+# import pmt
import pathlib
diff --git a/srt/daemon/radio_control/radio_process/radio_process.py b/srt/daemon/radio_control/radio_process/radio_process.py
index b2cba6df..0ef26941 100644
--- a/srt/daemon/radio_control/radio_process/radio_process.py
+++ b/srt/daemon/radio_control/radio_process/radio_process.py
@@ -14,12 +14,13 @@
from gnuradio.fft import window
from gnuradio import filter
from gnuradio import gr
-from gnuradio.filter import firdes
+# from gnuradio.filter import firdes
import sys
import signal
from argparse import ArgumentParser
-from gnuradio.eng_arg import eng_float, intx
-from gnuradio import eng_notation
+# from gnuradio.eng_arg import eng_float, intx
+from gnuradio.eng_arg import intx
+# from gnuradio import eng_notation
from gnuradio import zeromq
try:
@@ -29,10 +30,10 @@
import threading
from . import add_clock_tags
-import math
+# import math
import numpy as np
import osmosdr
-import time
+# import time
class radio_process(gr.top_block):
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..5b9f0f36 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
@@ -9,12 +9,13 @@
# GNU Radio version: 3.8.1.0
from gnuradio import gr
-from gnuradio.filter import firdes
+# from gnuradio.filter import firdes
import sys
import signal
from argparse import ArgumentParser
-from gnuradio.eng_arg import eng_float, intx
-from gnuradio import eng_notation
+# from gnuradio.eng_arg import eng_float, intx
+from gnuradio.eng_arg import intx
+# from gnuradio import eng_notation
from gnuradio import zeromq
import numpy as np
import gr_digital_rf
diff --git a/srt/daemon/radio_control/radio_save_spec_fits/radio_save_spec_fits.py b/srt/daemon/radio_control/radio_save_spec_fits/radio_save_spec_fits.py
index 05720a90..4085216d 100644
--- a/srt/daemon/radio_control/radio_save_spec_fits/radio_save_spec_fits.py
+++ b/srt/daemon/radio_control/radio_save_spec_fits/radio_save_spec_fits.py
@@ -9,12 +9,13 @@
# GNU Radio version: 3.8.1.0
from gnuradio import gr
-from gnuradio.filter import firdes
+# from gnuradio.filter import firdes
import sys
import signal
from argparse import ArgumentParser
-from gnuradio.eng_arg import eng_float, intx
-from gnuradio import eng_notation
+# from gnuradio.eng_arg import eng_float, intx
+from gnuradio.eng_arg import intx
+# from gnuradio import eng_notation
from gnuradio import zeromq
from . import save_fits_file
diff --git a/srt/daemon/radio_control/radio_save_spec_rad/radio_save_spec.py b/srt/daemon/radio_control/radio_save_spec_rad/radio_save_spec.py
index c009bb6b..67cb4629 100644
--- a/srt/daemon/radio_control/radio_save_spec_rad/radio_save_spec.py
+++ b/srt/daemon/radio_control/radio_save_spec_rad/radio_save_spec.py
@@ -9,12 +9,13 @@
# GNU Radio version: 3.8.1.0
from gnuradio import gr
-from gnuradio.filter import firdes
+# from gnuradio.filter import firdes
import sys
import signal
from argparse import ArgumentParser
-from gnuradio.eng_arg import eng_float, intx
-from gnuradio import eng_notation
+# from gnuradio.eng_arg import eng_float, intx
+from gnuradio.eng_arg import intx
+# from gnuradio import eng_notation
from gnuradio import zeromq
from . import save_rad_file
diff --git a/srt/daemon/rotor_control/motors.py b/srt/daemon/rotor_control/motors.py
index 24dddb0b..512f6337 100644
--- a/srt/daemon/rotor_control/motors.py
+++ b/srt/daemon/rotor_control/motors.py
@@ -3,6 +3,7 @@
Module for Controlling Different Motor Types over Serial
"""
+
import serial
from abc import ABC, abstractmethod
@@ -322,6 +323,323 @@ def stop(self):
# return (az_relative + self.az_limits[0], el_relative + self.el_limits[0])
+class CassiMotor(Motor):
+ """
+ http://www.ncra.tifr.res.in/rpl/facilities/3m-srt
+ Based on the h180 function from the C SRT code:
+ ftp://gemini.haystack.mit.edu/pub/web/src/source_srt_newsrtsource_ver9.tar.gz
+
+ Copied from H180Motor class with correction for Cassi Corp. motor type.
+ Corrections taken from the Java version of SRT. This motor has a linear
+ actuator for elevation movement SuperPowerJack QARL-3636+
+ """
+
+ # AZCOUNTS_PER_DEG = 52.0 * 27.0 / 120.0
+ # ELCOUNTS_PER_DEG = 52.0 * 27.0 / 120.0
+
+ # CASSI
+ # PTOLER = 1 # for encoders
+ COUNPERSTEP = 10000 # default large number for no stepping
+ AZCOUNTS_PER_DEG = 8.0 * 32.0 * 60.0 / (360.0 * 9.0) # default for CASSIMOUNT
+ # ROD = 1 # default to rod as on CASSIMOUNT
+ # Parameters described in: https://www.haystack.mit.edu/wp-content/uploads/2020/07/memo_SRT_017.pdf , note 5)
+ ROD1 = 14.25 # rigid arm length
+ ROD2 = 16.5 # distance from pushrod upper joint to el axis
+ ROD3 = 2.0 # pushrod collar offset
+ ROD4 = 110.0 # angle at horizon
+ ROD5 = 30.0 # pushrod counts per inch
+ # end CASSI
+
+ def __init__(
+ self, port, baudrate, az_limits, el_limits, counts_per_step=COUNPERSTEP
+ ):
+ """Initializer for the Cassi Motor, baudrate should be 2400.
+
+ Parameters
+ ----------
+ port : str
+ Serial Port Identifier String for Communicating with the Motor
+ baudrate : int
+ Baudrate for serial connection
+ az_limits : (float, float)
+ Tuple of Lower and Upper Azimuth Limits
+ el_limits : (float, float)
+ Tuple of Lower and Upper Elevation Limits
+ counts_per_step : int
+ Maximum number of counts to move per call to function
+ """
+ Motor.__init__(
+ self, port, az_limits=az_limits, el_limits=el_limits, baudrate=baudrate
+ ),
+ self.serial = serial.Serial(
+ port=port,
+ baudrate=baudrate, # 2400,
+ bytesize=serial.EIGHTBITS,
+ parity=serial.PARITY_NONE,
+ stopbits=serial.STOPBITS_ONE,
+ timeout=None,
+ )
+ if baudrate != 2400:
+ print(
+ f"The correct baud rate for the Cassi motor is 2400, while {baudrate} is parsed from the config file. Have you forgotten to change it?"
+ )
+ self.count_per_step = counts_per_step
+ self.az_lower_lim = az_limits[0]
+ self.el_lower_lim = el_limits[0]
+ self.az_count = 0.0
+ self.el_count = 0.0
+
+ def send_Cassi_cmd(self, az, el, stow):
+ """Sends a Command to the Cassi Motor
+
+ Parameters
+ ----------
+ az : float
+ Azimuth Coordinate to Point At
+ el : float
+ Elevation Coordinate to Point At
+ stow : bool
+ Whether or Not to Stow Antenna (makes az,el irrelevant)
+
+ Returns
+ -------
+ self.az_count, self.el_count : int
+ Current motos position
+ """
+
+ # mm Result, https://www1.phys.vt.edu/~jhs/phys3154/SRT%20Technical%20Supplement.pdf
+ # 0 decrease azimuth (CCW)
+ # 1 increase azimuth (CW)
+ # 2 decrease elevation
+ # 3 increase elevation
+
+ # print("D_az: ", az)
+ # print("D_el: ", el)
+ azz = (
+ az - self.az_lower_lim
+ ) # az to d1.azcmd w C i nie zgadza sie. Definiowana w app.py#L275, a tam jest brana z self.rotor_location z daemon.py#L601
+ # print("D1_0: ", azz)
+ # print("D1_1: ", az)
+ # print("D1_1: ", self.az_lower_lim)
+ ell = el - self.el_lower_lim
+ # print("D2: ", ell)
+ for axis in range(2):
+ mm = -1
+ count = 0 # number of “counts” of the reed microswitch on the drive gear to move
+ if stow:
+ # print("D2_2: stow")
+ if axis == 0:
+ mm = 0
+ else:
+ mm = 2
+ count = 8000
+ else:
+ if axis == 0:
+ # print("D3: axis==0")
+ acount = azz * CassiMotor.AZCOUNTS_PER_DEG - self.az_count
+ # print("D4: ", acount)
+ # print("D4_2: self.az_count - czy w drugiej iteracji jest wyliczona wczesniej wartosc? ", self.az_count)
+ if self.count_per_step and acount > self.count_per_step:
+ acount = self.count_per_step
+ # print("D5: ", acount)
+ if self.count_per_step and acount < -self.count_per_step:
+ acount = -self.count_per_step
+ # print("D6: ", acount)
+ if acount > 0:
+ count = (
+ acount + 0.5
+ ) # 0.5 prevent rounding down. Change to math.ceil() ?
+ # print("D7: ", count)
+ else:
+ count = acount - 0.5
+ # print("D8: ", count)
+ if count > 0:
+ mm = 1
+ # print("D9: ", mm)
+ if count < 0:
+ mm = 0
+ # print("D10: ", mm)
+ if axis == 1:
+ # print("D11: axis==1")
+
+ # CASSI
+ lenzero = (
+ self.ROD1 * self.ROD1
+ + self.ROD2 * self.ROD2
+ - 2.0
+ * self.ROD1
+ * self.ROD2
+ * cos((self.ROD4 - self.el_lower_lim) * pi / 180.0)
+ - self.ROD3 * self.ROD3
+ )
+ if lenzero >= 0.0:
+ lenzero = sqrt(lenzero)
+ else:
+ lenzero = 0
+ acount = (
+ self.ROD1 * self.ROD1
+ + self.ROD2 * self.ROD2
+ - 2.0
+ * self.ROD1
+ * self.ROD2
+ * cos((self.ROD4 - (ell + self.el_lower_lim)) * pi / 180.0)
+ - self.ROD3 * self.ROD3
+ )
+ if acount >= 0.0:
+ acount = (-sqrt(acount) + lenzero) * self.ROD5
+ else:
+ acount = 0
+ acount = acount - self.el_count
+ # print("D11_2: self.el_count - czy w drugiej iteracji jest wyliczona wczesniej wartosc? ", self.el_count)
+ # end CASSI
+
+ # acount = ell * CassiMotor.ELCOUNTS_PER_DEG - self.el_count
+ # print("D12: ", acount)
+ if self.count_per_step and acount > self.count_per_step:
+ acount = self.count_per_step
+ # print("D13: ", acount)
+ if self.count_per_step and acount < -self.count_per_step:
+ acount = -self.count_per_step
+ # print("D14: ", acount)
+ if acount > 0:
+ count = acount + 0.5
+ # print("D15: ", count)
+ else:
+ count = acount - 0.5
+ # print("D16: ", count)
+ if count > 0:
+ mm = 3
+ # print("D17: ", mm)
+ if count < 0:
+ mm = 2
+ # print("D18: ", mm)
+ if count < 0:
+ count = -count
+ # print("D19: ", count)
+ if mm >= 0 and count:
+ cmd_string = " move %d %d%1c" % (mm, count, 13)
+ # print("D20: ", cmd_string)
+ self.serial.write(cmd_string.encode("ascii"))
+ resp = ""
+ sleep(0.01)
+ im = 0
+ i = 0
+ while i < 32:
+ ch = int.from_bytes(self.serial.read(1), byteorder="big")
+ # print("D21_0: ", ch)
+ sleep(0.01)
+ if i < 32:
+ resp += chr(ch)
+ # print("D21_1: ", resp)
+ i += 1
+ if ch == 13 or ch == 10:
+ # print("D22: ", ch)
+ break
+ status = i
+ # print("D23_0: ", status)
+ sleep(0.1)
+ # print("D23_1: ", resp)
+ for i in range(status):
+ if (
+ resp[i] == "M" or resp[i] == "T"
+ ): # Move, Timeout. Timeout means STOW or limit switches
+ im = i
+ # print("D23_2: ", im)
+ ccount = int(
+ resp[im:status].split(" ")[-3]
+ ) # rozdziela resp (spacja jako delimiter) i zwraca druga czesc jako int
+ # print("D24: ", ccount) # TU SIE ZACZYNA ROZNIC
+ if resp[im] == "M":
+ # print("D25_0: ", resp[im])
+ if mm == 1:
+ self.az_count += ccount
+ if mm == 0:
+ self.az_count -= ccount
+ if mm == 3:
+ self.el_count += ccount
+ if mm == 2:
+ self.el_count -= ccount
+ # print("D25_1: ", self.az_count)
+ # print("D25_2: ", self.el_count)
+ if resp[im] == "T":
+ # print("D26: ", resp[im])
+ if mm == 1:
+ self.az_count += count
+ if mm == 0:
+ self.az_count -= count
+ if mm == 3:
+ self.el_count += count
+ if mm == 2:
+ self.el_count -= count
+ if stow:
+ self.az_count = 0
+ self.el_count = 0
+ # print("D27: tu nie ma self.serial close, a w C jest zamykanie")
+ return self.az_count, self.el_count
+
+ def point(self, az, el):
+ """Points an Cassi Motor at a Certain Az, El
+
+ Parameters
+ ----------
+ az : float
+ Azimuth Coordinate to Point At
+ el : float
+ Elevation Coordinate to Point At
+
+ Returns
+ -------
+ None
+ """
+ self.send_Cassi_cmd(az, el, False)
+ return self.status()
+
+ def status(self):
+ """Requests the Current Location of the Cassi Motor
+
+ Returns
+ -------
+ (float, float)
+ Current Azimuth and Elevation Coordinate as a Tuple of Floats
+ """
+ azz = self.az_count / CassiMotor.AZCOUNTS_PER_DEG
+ # ell = self.el_count / CassiMotor.ELCOUNTS_PER_DEG # CASSI
+
+ # CASSI
+ lenzero = (
+ self.ROD1 * self.ROD1
+ + self.ROD2 * self.ROD2
+ - 2.0
+ * self.ROD1
+ * self.ROD2
+ * cos((self.ROD4 - self.el_lower_lim) * pi / 180.0)
+ - self.ROD3 * self.ROD3
+ )
+ # print("D0_0: ", self.el_lower_lim)
+ # print("D0_1: ", lenzero)
+ if lenzero >= 0.0:
+ lenzero = sqrt(lenzero)
+ else:
+ lenzero = 0
+ temp = lenzero - self.el_count / self.ROD5
+ temp = (
+ self.ROD1 * self.ROD1
+ + self.ROD2 * self.ROD2
+ - self.ROD3 * self.ROD3
+ - temp * temp
+ ) / (2.0 * self.ROD1 * self.ROD2)
+ # print("D0_2: ", temp)
+ ell = -acos(temp) * 180 / pi + self.ROD4 - self.el_lower_lim
+ # print("D0_3: ", ell)
+ # end CASSI
+
+ az = azz + self.az_lower_lim
+ el = (
+ ell + self.el_lower_lim
+ ) # kolo frazy azel w Javie jest to wyswietlane ze zmiennej ell. W Co to sie chyba w ogole nie wyswietla. W sport.java jest też wyliczana ellnow
+ return az, el
+
+
class H180Motor(Motor): # TODO: Test!
"""
Class for Controlling any ROT2 Protocol-Supporting Motor (e.g. SPID Motors)
@@ -349,7 +667,10 @@ def __init__(self, port, baudrate, az_limits, el_limits, counts_per_step=100):
counts_per_step : int
Maximum number of counts to move per call to function
"""
- Motor.__init__(self, port, az_limits, el_limits)
+ # Motor.__init__(self, port, az_limits, el_limits)
+ Motor.__init__(
+ self, port, az_limits=az_limits, el_limits=el_limits, baudrate=baudrate
+ )
self.serial = serial.Serial(
port=port,
baudrate=baudrate, # 2400,
@@ -358,6 +679,10 @@ def __init__(self, port, baudrate, az_limits, el_limits, counts_per_step=100):
stopbits=serial.STOPBITS_ONE,
timeout=None,
)
+ if baudrate != 2400:
+ print(
+ f"The correct baud rate for the H180 motor is 2400, while {baudrate} is parsed from the config file. Have you forgotten to change it?"
+ )
self.count_per_step = counts_per_step
self.az_lower_lim = az_limits[0]
self.el_lower_lim = el_limits[0]
@@ -442,7 +767,9 @@ def send_h180_cmd(self, az, el, stow):
for i in range(status):
if resp[i] == "M" or resp[i] == "T":
im = i
- ccount = int(resp[im:status].split(" ")[-1])
+ ccount = int(
+ resp[im:status].split(" ")[-1]
+ ) # for Cassi motor correct value here is -3
if resp[im] == "M":
if mm == 1:
self.az_count += ccount
@@ -465,6 +792,8 @@ def send_h180_cmd(self, az, el, stow):
self.az_count = 0
self.el_count = 0
+ # return self.az_count, self.el_count # for Cassi motor this needs to be here
+
def point(self, az, el):
"""Points an H180 Motor at a Certain Az, El
diff --git a/srt/daemon/rotor_control/rotors.py b/srt/daemon/rotor_control/rotors.py
index 04caaf0c..3a294473 100644
--- a/srt/daemon/rotor_control/rotors.py
+++ b/srt/daemon/rotor_control/rotors.py
@@ -3,9 +3,10 @@
Module for Managing Different Motor Objects
"""
+
from enum import Enum
-from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor
+from .motors import NoMotor, Rot2Motor, H180Motor, PushRodMotor, CassiMotor
def angle_within_range(angle, limits):
@@ -25,6 +26,7 @@ class RotorType(Enum):
ROT2 = "ALFASPID"
H180 = "H180MOUNT"
PUSH_ROD = "PUSHROD"
+ CASSI = "CASSI"
class Rotor:
@@ -56,8 +58,10 @@ def __init__(self, motor_type, port, baudrate, az_limits, el_limits):
self.motor = Rot2Motor(port, baudrate, az_limits, el_limits)
elif motor_type == RotorType.H180 or motor_type == RotorType.H180.value:
self.motor = H180Motor(port, baudrate, az_limits, el_limits)
- elif motor_type == RotorType.PUSH_ROD == RotorType.PUSH_ROD.value:
+ elif motor_type == RotorType.PUSH_ROD or motor_type == RotorType.PUSH_ROD.value:
self.motor = PushRodMotor(port, baudrate, az_limits, el_limits)
+ elif motor_type == RotorType.CASSI or motor_type == RotorType.CASSI.value:
+ self.motor = CassiMotor(port, baudrate, az_limits, el_limits)
else:
raise ValueError("Not a known motor type")
diff --git a/srt/daemon/utilities/functions.py b/srt/daemon/utilities/functions.py
index b044e4e3..49aeb9bb 100644
--- a/srt/daemon/utilities/functions.py
+++ b/srt/daemon/utilities/functions.py
@@ -3,8 +3,10 @@
Extra Functions Condensed for Ease-of-Use
"""
+
import zmq
import numpy as np
+from math import isqrt
def angle_within_range(actual_angle, desired_angle, bounds=0.5):
@@ -156,3 +158,20 @@ def npoint_interp(az, el, val, d_az, d_el, nout=100):
)
return azarr, elarr, val_out
+
+
+def is_square(i: int) -> bool:
+ """Check if input is a square of nautral number
+
+ Parameters
+ ----------
+ i : int
+ Number to chceck
+
+ Returns
+ -------
+ bool
+ If input is a square of nautral number
+
+ """
+ return i == isqrt(i) ** 2
diff --git a/srt/daemon/utilities/object_tracker.py b/srt/daemon/utilities/object_tracker.py
index e2abc608..5e5f31d5 100644
--- a/srt/daemon/utilities/object_tracker.py
+++ b/srt/daemon/utilities/object_tracker.py
@@ -3,7 +3,8 @@
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
from astropy.coordinates import ICRS, Galactic, FK4, CIRS, AltAz
from astropy.utils.iers.iers import conf
from astropy.table import Table
@@ -110,9 +111,9 @@ def calculate_az_el(self, name, time, alt_az_frame):
(az, el) Tuple
"""
if name == "Sun":
- alt_az = get_sun(time).transform_to(alt_az_frame)
+ alt_az = get_body("sun", time).transform_to(alt_az_frame)
elif name == "Moon":
- alt_az = get_moon(time, self.location).transform_to(alt_az_frame)
+ alt_az = get_body("moon", time, self.location).transform_to(alt_az_frame)
else:
alt_az = self.sky_coords[self.sky_coord_names[name]].transform_to(
alt_az_frame
@@ -138,10 +139,10 @@ def calculate_vlsr(self, name, time, frame):
vlsr in km/s.
"""
if name == "Sun":
- tframe = get_sun(time).transform_to(frame)
+ tframe = get_body("sun", time).transform_to(frame)
vlsr = tframe.radial_velocity_correction(obstime=time)
elif name == "Moon":
- tframe = get_moon(time).transform_to(frame)
+ tframe = get_body("moon", time).transform_to(frame)
vlsr = tframe.radial_velocity_correction(obstime=time)
else:
tframe = self.sky_coord_names[name].transform_to(frame)
@@ -149,13 +150,13 @@ def calculate_vlsr(self, name, time, frame):
return vlsr.to(u.km / u.s).value
- def calculate_vlsr_azel(self,az_el, time=None):
+ 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
+ Azimuth and Elevation
time : AstroPy Time Obj
Time of Conversion
@@ -167,7 +168,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
@@ -175,11 +176,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)
+ 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
-
+ 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
@@ -266,13 +267,15 @@ def get_azimuth_elevation(self, name, time_offset):
return self.calculate_az_el(
name, time, AltAz(obstime=time, location=self.location)
)
+
def get_all_vlsr(self):
return self.vlsr_dict
+
def get_vlsr(self, name, time_offset=0):
-
- if time_offset==0:
+
+ 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)
\ No newline at end of file
+ return self.calculate_vlsr(name, time, frame)
diff --git a/srt/dashboard/app.py b/srt/dashboard/app.py
index 9fe96e0b..5574aa17 100644
--- a/srt/dashboard/app.py
+++ b/srt/dashboard/app.py
@@ -50,7 +50,9 @@ def generate_app(config_dir, config_dict):
config_dict["CONFIG_DIR"] = config_dir
# Set Up Flash and Dash Objects
- server = flask.Flask(__name__)
+ server = flask.Flask(
+ __name__
+ ) # these messages "127.0.0.1 - - [16/Mar/2024 12:10:13] "POST / HTTP/1.1" 200 -"" are generated by Flask
app = dash.Dash(
__name__,
server=server,
@@ -68,10 +70,11 @@ def generate_app(config_dir, config_dict):
command_thread = CommandThread(port=5556)
command_thread.start()
- raw_spectrum_thread = SpectrumThread(port=5561)
+ history_length = config_dict["SPECTRUM_HISTORY_LENGTH"]
+ raw_spectrum_thread = SpectrumThread(port=5561, history_length=history_length)
raw_spectrum_thread.start()
- cal_spectrum_thread = SpectrumThread(port=5563)
+ cal_spectrum_thread = SpectrumThread(port=5563, history_length=history_length)
cal_spectrum_thread.start()
# Dictionary of Pages and matching URL prefixes
@@ -271,6 +274,7 @@ def update_status_display(n):
bandwidth = np.nan
status_string = "SRT Not Connected"
vlsr = np.nan
+ rec_status = "No"
else:
az = status["motor_azel"][0]
el = status["motor_azel"][1]
@@ -279,6 +283,9 @@ def update_status_display(n):
cf = status["center_frequency"]
bandwidth = status["bandwidth"]
vlsr = status["vlsr"]
+ rec_status = "No"
+ if "None" not in status["radio_save_task"]:
+ rec_status = "Yes"
time_dif = time() - status["time"]
if time_dif > 5:
status_string = "SRT Daemon Not Available"
@@ -287,6 +294,16 @@ def update_status_display(n):
else:
status_string = "SRT In Use!"
+ if rec_status == "No":
+ status_string = f"""
+ # {status_string}
+ - Currently recording: No"""
+
+ if rec_status == "Yes":
+ status_string = f"""
+ # {status_string}
+ - Currently recording: **Yes**"""
+
status_string = f"""
#### {status_string}
- Motor Az, El: {az:.1f}, {el:.1f} deg
diff --git a/srt/dashboard/layouts/graphs.py b/srt/dashboard/layouts/graphs.py
index 4dfd4b8f..f89deba9 100644
--- a/srt/dashboard/layouts/graphs.py
+++ b/srt/dashboard/layouts/graphs.py
@@ -5,8 +5,13 @@
"""
import plotly.graph_objects as go
-from datetime import datetime
+from datetime import datetime, timezone
import numpy as np
+from math import dist
+from tzlocal import get_localzone
+from astropy.coordinates import SkyCoord, EarthLocation, AltAz
+import astropy.units as u
+from astropy.time import Time
def generate_az_el_graph(
@@ -17,7 +22,16 @@ def generate_az_el_graph(
stow_position,
cal_position,
horizon_points,
- beam_width
+ beam_width,
+ rotor_loc_npoint_live,
+ motor_cmd_azel,
+ minimal_arrows_distance,
+ npoint_arrows,
+ motor_type,
+ station,
+ display_lim,
+ draw_ecliptic,
+ draw_equator,
):
"""Generates Figure for Displaying AzEl Locations
@@ -44,13 +58,16 @@ def generate_az_el_graph(
-------
Plotly Figure of Azimuth and Elevation Graph
"""
- fig = go.Figure()
-
- az_lower_display_lim = 0
- az_upper_display_lim = 360
- el_lower_display_lim = 0
- el_upper_display_lim = 90
+ fig = go.Figure(
+ layout={
+ "uirevision": True,
+ }
+ )
+ az_lower_display_lim = display_lim[0]
+ az_upper_display_lim = display_lim[1]
+ el_lower_display_lim = display_lim[2]
+ el_upper_display_lim = display_lim[3]
# Markers for celestial objects
fig.add_trace(
@@ -58,6 +75,7 @@ def generate_az_el_graph(
x=[points_dict[name][0] for name in points_dict],
y=[points_dict[name][1] for name in points_dict],
text=[name for name in points_dict],
+ hoverinfo=["text", "name"],
name="Celestial Objects",
mode="markers+text",
textposition="top center",
@@ -65,42 +83,145 @@ def generate_az_el_graph(
)
)
- # Marker for visability, 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
+ # Real size Sun
+ fig.add_shape(
+ type="circle",
+ xref="x",
+ yref="y",
+ x0=points_dict["Sun"][0] - 0.25,
+ y0=points_dict["Sun"][1] - 0.25,
+ x1=points_dict["Sun"][0] + 0.25,
+ y1=points_dict["Sun"][1] + 0.25,
+ fillcolor="gold",
+ )
- 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)]
+ # Real size Moon
+ fig.add_shape(
+ type="circle",
+ xref="x",
+ yref="y",
+ x0=points_dict["Moon"][0] - 0.25,
+ y0=points_dict["Moon"][1] - 0.25,
+ x1=points_dict["Moon"][0] + 0.25,
+ y1=points_dict["Moon"][1] + 0.25,
+ fillcolor="silver",
+ )
- 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]
+ # N-point scan
+ if rotor_loc_npoint_live:
+ # Markers
+ fig.add_trace(
+ go.Scatter(
+ x=[i[0] for i in rotor_loc_npoint_live],
+ y=[i[1] for i in rotor_loc_npoint_live],
+ name="N-point scan positions",
+ mode="markers",
+ marker_color=["greenyellow" for _ in rotor_loc_npoint_live],
+ )
)
+ # Arrows showing n-point scan route
+ if npoint_arrows == True:
+ if len(rotor_loc_npoint_live) > 1:
+ azzz = [col[0] for col in rotor_loc_npoint_live]
+ elll = [col[1] for col in rotor_loc_npoint_live]
+ x_end = azzz[1:]
+ x_start = azzz[:-1]
+ y_end = elll[1:]
+ y_start = elll[:-1]
+ for x0, y0, x1, y1 in zip(x_end, y_end, x_start, y_start):
+ fig.add_annotation(
+ x=x0,
+ y=y0,
+ ax=x1,
+ ay=y1,
+ axref="x",
+ ayref="y",
+ xref="x",
+ yref="y",
+ arrowcolor="limegreen",
+ arrowwidth=2.5,
+ arrowside="end",
+ arrowsize=1,
+ arrowhead=2,
+ opacity=0.3,
+ )
+
+ # Arrows showing telescope route
+ if dist(current_location, motor_cmd_azel) > minimal_arrows_distance:
+ # If the motor moves in both axis at a time
+ if motor_type in ("NONE", "ALFASPID", "PUSHROD"): # IS THIS LIST OK?
+ fig.add_annotation(
+ ax=current_location[0],
+ ay=current_location[1],
+ axref="x",
+ ayref="y",
+ x=motor_cmd_azel[0],
+ y=motor_cmd_azel[1],
+ xref="x",
+ yref="y",
+ arrowcolor="red",
+ arrowwidth=2.5,
+ arrowside="end",
+ arrowsize=1,
+ arrowhead=4,
+ opacity=0.4,
+ )
+ # If the motor moves in only one of the axis at a time
+ if motor_type in ("CASSI", "H180MOUNT"):
+ x_start = [current_location[0], motor_cmd_azel[0]]
+ x_end = [motor_cmd_azel[0], motor_cmd_azel[0]]
+ y_start = [current_location[1], current_location[1]]
+ y_end = [current_location[1], motor_cmd_azel[1]]
+
+ for x0, y0, x1, y1 in zip(x_end, y_end, x_start, y_start):
+ fig.add_annotation(
+ x=x0,
+ y=y0,
+ ax=x1,
+ ay=y1,
+ axref="x",
+ ayref="y",
+ xref="x",
+ yref="y",
+ arrowcolor="red",
+ arrowwidth=2.5,
+ arrowside="end",
+ arrowsize=1,
+ arrowhead=4,
+ opacity=0.4,
+ )
+
+ # Marker for visability, basically beamwidth with azimuth stretched out for high elevation angles.
+ az_l = current_location[0]
+ el_l = current_location[1]
+ fig.add_shape(
+ type="circle",
+ xref="x",
+ yref="y",
+ x0=az_l - 0.5 * beam_width,
+ y0=el_l - 0.5 * beam_width,
+ x1=az_l + 0.5 * beam_width,
+ y1=el_l + 0.5 * beam_width,
+ fillcolor="rgba(147,112,219, .2)",
+ line=dict(
+ color="RoyalBlue",
+ width=1,
+ ),
+ showlegend=True,
+ name="Visability",
)
fig.add_trace(
go.Scatter(
x=[az_l],
y=[el_l],
- text=["Antenna Location"],
+ text="Antenna Location",
name="Current Location",
mode="markers+text",
textposition="bottom center",
- marker_color=["rgba(0, 0, 152, .8)"],
+ marker=dict(symbol="x", color=["rgba(0, 0, 152, .8)"]),
)
- )
+ )
fig.add_trace(
go.Scatter(
@@ -110,7 +231,9 @@ def generate_az_el_graph(
name="Other Locations",
mode="markers+text",
textposition="top center",
- marker_color=["rgba(0, 152, 0, .8)", "rgba(0, 152, 0, .8)"],
+ marker=dict(
+ symbol="diamond", color=["rgba(0, 152, 0, .8)", "rgba(0, 152, 0, .8)"]
+ ),
)
)
@@ -208,6 +331,37 @@ def generate_az_el_graph(
),
)
+ # Windrose lines and letters
+ x_pos = [0, 90, 180, 270, 360]
+ rose_lettter = ["N", "E", "S", "W", "N"]
+ for a, b in zip(x_pos, rose_lettter):
+ fig.add_annotation(
+ dict(
+ font=dict(color="darkgray", size=14),
+ x=a,
+ y=1.0,
+ showarrow=False,
+ text=b,
+ textangle=0,
+ xref="x",
+ yref="paper",
+ )
+ )
+
+ for val in [90, 180, 270]:
+ fig.add_shape(
+ type="line",
+ x0=val,
+ y0=-90,
+ x1=val,
+ y1=90,
+ line=dict(
+ color="LightBlue",
+ width=1,
+ dash="dashdot",
+ ),
+ )
+
# Set axes ranges
fig.update_layout(
title={
@@ -227,14 +381,45 @@ def generate_az_el_graph(
xaxis_title="Azimuth",
yaxis_title="Elevation",
legend=dict(orientation="h", yanchor="bottom", y=1.02, xanchor="right", x=1),
+ # ghostwhite, azure, # https://stackoverflow.com/a/72502441/6764984
+ plot_bgcolor="rgb(252,252,252)",
)
fig.update_xaxes(range=[az_lower_display_lim, az_upper_display_lim])
fig.update_yaxes(range=[el_lower_display_lim, el_upper_display_lim])
+ # Draw ecliptic plane
+ if draw_ecliptic == True:
+ ecl_el, ecl_az = generate_ecliptic_plane(station)
+ fig.add_trace(
+ go.Scatter(
+ x=[point for point in ecl_az],
+ y=[point for point in ecl_el],
+ name="Ecliptic",
+ mode="lines",
+ opacity=0.5,
+ textposition="top center",
+ line=dict(color="MediumPurple", width=1, dash="dash"),
+ )
+ )
+
+ # Draw equator plane
+ if draw_equator == True:
+ ecl_el, ecl_az = generate_equator_plane(station) # 0.0041 sec @i5-11400H @ 2.70GHz
+ fig.add_trace(
+ go.Scatter(
+ x=[point for point in ecl_az],
+ y=[point for point in ecl_el],
+ name="Earth's equator",
+ mode="lines",
+ textposition="top center",
+ line=dict(color="LightSkyBlue", width=1, dash="dot"),
+ )
+ )
+
return fig
-def generate_power_history_graph(tsys, tcal, cal_pwr, spectrum_history):
+def generate_power_history_graph(tsys, tcal, cal_pwr, spectrum_history, gui_timezone):
"""Generates a Graph of the Power History
Parameters
@@ -259,15 +444,23 @@ def generate_power_history_graph(tsys, tcal, cal_pwr, spectrum_history):
pwr = (tsys + tcal) * p / (a * cal_pwr)
power_history.insert(0, (t, pwr))
if power_history is None or len(power_history) == 0:
- return ""
+ return emptygraph("Time", "Calibrated Power", title="Power vs Time", height=300)
power_time, power_vals = zip(*power_history)
+ if gui_timezone == "UTC":
+ xaxis_title = "Time (UTC)"
+ x_labels = [datetime.fromtimestamp(t, timezone.utc) for t in power_time]
+ else:
+ xaxis_title = "Time (local)"
+ x_labels = [
+ datetime.fromtimestamp(t, timezone.utc).astimezone(get_localzone())
+ for t in power_time
+ ]
+
fig = go.Figure(
- data=go.Scatter(
- x=[datetime.utcfromtimestamp(t) for t in power_time], y=power_vals
- ),
+ data=go.Scatter(x=x_labels, y=power_vals),
layout={
"title": "Power vs Time",
- "xaxis_title": "Time (UTC)",
+ "xaxis_title": xaxis_title,
"yaxis_title": "Calibrated Power",
"height": 300,
"margin": dict(
@@ -283,6 +476,95 @@ def generate_power_history_graph(tsys, tcal, cal_pwr, spectrum_history):
return fig
+def generate_waterfall_graph(
+ bandwidth, cf, spectrum_history, waterfall_length, gui_timezone
+):
+ """Generates a Waterfall Graph of Spectrum Data
+
+ Parameters
+ ----------
+ bandwidth : float
+ Bandwidth of the Incoming Spectra
+ cf : float
+ Center Frequency of the Incoming Spectra
+ spectrum_history : [(int, ndarary)]
+ List of Spectrum Samples
+
+ Returns
+ -------
+ Plotly Graph Object of Waterfall Spectrum
+ """
+ waterfall = []
+ timestamps = []
+ if len(spectrum_history) > 0:
+ spectrum_history_len = len(spectrum_history)
+ how_many_spectra = min(spectrum_history_len, waterfall_length)
+ spectrum_history_last_n_els = spectrum_history[:how_many_spectra]
+
+ for t, spectrum in spectrum_history_last_n_els:
+ waterfall.append(list(spectrum))
+ timestamps.append(t)
+ if cf > pow(10, 9):
+ cf /= pow(10, 9)
+ bandwidth /= pow(10, 9)
+ xaxis = "Frequency (GHz)"
+ elif cf > pow(10, 6):
+ cf /= pow(10, 6)
+ bandwidth /= pow(10, 6)
+ xaxis = "Frequency (MHz)"
+ elif cf > pow(10, 3):
+ cf /= pow(10, 3)
+ bandwidth /= pow(10, 3)
+ xaxis = "Frequency (kHz)"
+ else:
+ xaxis = "Frequency (Hz)"
+ if gui_timezone == "UTC":
+ yaxis_title = "Time (UTC)"
+ else:
+ yaxis_title = "Time (local)"
+ fig = go.Figure(
+ layout={
+ "title": "Raw Spectrum History",
+ "xaxis_title": xaxis,
+ "yaxis_title": yaxis_title,
+ "height": 300,
+ "margin": dict(
+ l=20,
+ r=20,
+ b=20,
+ t=30,
+ pad=4,
+ ),
+ "uirevision": True,
+ },
+ )
+ data_range = (
+ np.linspace(-bandwidth / 2, bandwidth / 2, num=len(waterfall[0])) + cf
+ )
+ if gui_timezone == "UTC":
+ y_labels = [datetime.fromtimestamp(t, timezone.utc) for t in timestamps]
+ else:
+ y_labels = [
+ datetime.fromtimestamp(t, timezone.utc).astimezone(get_localzone())
+ for t in timestamps
+ ]
+
+ # https://plotly.com/python/builtin-colorscales/
+ fig.add_trace(
+ go.Heatmap(
+ colorbar={"title": "Temp.
(Unitless)"},
+ y=y_labels,
+ x=data_range,
+ z=waterfall,
+ colorscale="RdBu_r",
+ )
+ )
+
+ return fig
+ else:
+ return ""
+
+
def generate_spectrum_graph(bandwidth, cf, spectrum, is_spec_cal):
"""Generates a Graph of Spectrum Data
@@ -363,7 +645,7 @@ def generate_spectrum_graph(bandwidth, cf, spectrum, is_spec_cal):
return fig
-def emptygraph(xlabel, ylabel, title):
+def emptygraph(xlabel, ylabel, **kwargs):
"""Creates an empty figure.
Parameters
@@ -374,16 +656,28 @@ def emptygraph(xlabel, ylabel, title):
String for ylabel.
title : str
String for title.
+ **kwargs : int
+ Hieght of the figure.
Returns
-------
fig : plotly.fig
Figure object.
"""
-
- fig = go.Figure(
- layout={"title": title, "xaxis_title": xlabel, "yaxis_title": ylabel}
- )
+ height = kwargs.get("height", None)
+ title = kwargs.get("title", None)
+ if height and title:
+ layout = {
+ "title": title,
+ "xaxis_title": xlabel,
+ "yaxis_title": ylabel,
+ "height": height,
+ }
+ if not height:
+ layout = {"title": title, "xaxis_title": xlabel, "yaxis_title": ylabel}
+ if (not height) and (not title):
+ layout = {"xaxis_title": xlabel, "yaxis_title": ylabel}
+ fig = go.Figure(layout=layout)
return fig
@@ -400,7 +694,7 @@ def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides):
d_az : float
Resolution of power measurements in the azimuth direction.
d_el : float
- REsolution of power measurements in elevation direction.
+ 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
@@ -415,6 +709,7 @@ def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides):
"""
# create the output grid
+
az_in = np.array(az_in)
el_in = np.array(el_in)
az_a = np.linspace(az_in.min(), az_in.max(), 100)
@@ -449,6 +744,7 @@ def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides):
"title": "N-Point Scan",
"xaxis_title": "Normalized x",
"yaxis_title": "Normalized y",
+ "height": 300,
"uirevision": True,
},
)
@@ -472,6 +768,63 @@ def generate_npoint(az_in, el_in, d_az, d_el, pow_in, cent, sides):
return fig
+def generate_bswitch_graph(power_bswitch_live, num_beamswitches):
+ fig = go.Figure(
+ layout={
+ "title": "Beam switch",
+ "xaxis_title": "Position",
+ "yaxis_title": "Power",
+ "height": 300,
+ "uirevision": True,
+ "xaxis_range": [0.75, 3.25],
+ },
+ )
+ x_axis_points = [1, 2, 3, 2]
+ x_axis_full = x_axis_points * num_beamswitches
+ power_bswitch_live_len = len(power_bswitch_live)
+ x_axis = x_axis_full[:power_bswitch_live_len]
+ fig.add_trace(
+ go.Scatter(
+ x=x_axis,
+ y=power_bswitch_live,
+ mode="markers",
+ opacity=0.5,
+ marker=dict(
+ color="green", size=10, line=dict(color="MediumPurple", width=1)
+ ),
+ )
+ )
+ left = power_bswitch_live[0::4]
+ target = power_bswitch_live[1::2]
+ right = power_bswitch_live[2::4]
+ background = (sum(left) + sum(right)) / 2
+ SN = round(sum(target) / background, 3)
+ annot_text = "S/N: " + str(SN)
+ fig.add_annotation(
+ x=2.5,
+ y=np.mean(power_bswitch_live),
+ xref="x",
+ yref="y",
+ text=annot_text,
+ showarrow=False,
+ font=dict(family="Courier New, monospace", size=16, color="#ffffff"),
+ align="center",
+ bordercolor="#c7c7c7",
+ borderwidth=2,
+ borderpad=6,
+ bgcolor="#ff7f0e",
+ opacity=0.8,
+ )
+ fig.update_layout(
+ xaxis=dict(
+ tickmode="array",
+ tickvals=[1, 2, 3],
+ ticktext=["Left offset", "Target", "Right offset"],
+ )
+ )
+ return fig
+
+
def sinc_interp2d(x, y, values, dx, dy, xout, yout):
"""Perform a sinc interpolation
@@ -506,3 +859,73 @@ def sinc_interp2d(x, y, values, dx, dy, xout, yout):
val_out += float(v_c) * np.sinc(x_1) * np.sinc(y_1)
return val_out
+
+
+def generate_ecliptic_plane(station):
+ """Generates the ecliptic plane
+
+ Parameters
+ ----------
+ None
+
+ Returns
+ -------
+ el, az : float, float
+ 1-d lists
+ """
+
+ observer_lat = (station["latitude"],)
+ observer_lon = (station["longitude"],)
+ observer_elevation = 0
+ location = EarthLocation.from_geodetic(
+ lat=observer_lat * u.deg,
+ lon=observer_lon * u.deg,
+ height=observer_elevation * u.m,
+ )
+
+ lon_ecl = np.linspace(0, 360, 100)
+ lat_ecl = np.zeros(100)
+
+ ecliptic_plane = SkyCoord(
+ lon_ecl, lat_ecl, unit=u.deg, frame="barycentricmeanecliptic"
+ )
+ ecliptic_altaz = ecliptic_plane.transform_to(
+ AltAz(obstime=Time.now(), location=location)
+ )
+ el, az = ecliptic_altaz.alt.deg.tolist(), ecliptic_altaz.az.deg.tolist()
+
+ return el, az
+
+
+def generate_equator_plane(station):
+ """Generates the equator plane
+
+ Parameters
+ ----------
+ None
+
+ Returns
+ -------
+ el, az : float, float
+ 1-d lists
+ """
+
+ observer_lat = (station["latitude"],)
+ observer_lon = (station["longitude"],)
+ observer_elevation = 0
+ location = EarthLocation.from_geodetic(
+ lat=observer_lat * u.deg,
+ lon=observer_lon * u.deg,
+ height=observer_elevation * u.m,
+ )
+
+ lon_eq = np.linspace(0, 360, 100)
+ lat_eq = np.zeros(100)
+
+ equator_plane = SkyCoord(lon_eq, lat_eq, unit=u.deg)
+ equator_altaz = equator_plane.transform_to(
+ AltAz(obstime=Time.now(), location=location)
+ )
+ el, az = equator_altaz.alt.deg.tolist(), equator_altaz.az.deg.tolist()
+
+ return el, az
diff --git a/srt/dashboard/layouts/monitor_page.py b/srt/dashboard/layouts/monitor_page.py
index 6222ea29..f1e8fa8e 100644
--- a/srt/dashboard/layouts/monitor_page.py
+++ b/srt/dashboard/layouts/monitor_page.py
@@ -9,14 +9,14 @@
try:
from dash import dcc
except:
- import dash_core_components as dcc
+ import dash_core_components as dcc # Dash 1.x
import dash_bootstrap_components as dbc
try:
from dash import html
except:
- import dash_html_components as html
+ import dash_html_components as html # Dash 1.x
from dash.exceptions import PreventUpdate
@@ -24,16 +24,17 @@
from pathlib import Path
from time import time
-import base64
+from base64 import b64decode
import io
-import numpy as np
from .navbar import generate_navbar
from .graphs import (
generate_az_el_graph,
generate_power_history_graph,
+ generate_waterfall_graph,
generate_spectrum_graph,
generate_npoint,
+ generate_bswitch_graph,
emptygraph,
)
@@ -45,18 +46,33 @@ def generate_first_row():
-------
Div Containing First Row Objects
"""
+ config = {
+ "displaylogo": False,
+ "scrollZoom": True,
+ "modeBarButtonsToAdd": [
+ "togglehover",
+ "togglespikelines",
+ "drawline",
+ "drawopenpath",
+ "drawclosedpath",
+ "drawcircle",
+ "drawrect",
+ "eraseshape",
+ ],
+ }
+
return html.Div(
[
html.Div(
[
html.Div(
- [dcc.Graph(id="power-graph")],
+ [dcc.Graph(id="power-graph", config=config)],
className="pretty_container six columns",
),
html.Div(
[
- dcc.Graph(id="cal-spectrum-histogram"),
- dcc.Graph(id="raw-spectrum-histogram"),
+ dcc.Graph(id="cal-spectrum-histogram", config=config),
+ dcc.Graph(id="raw-spectrum-histogram", config=config),
],
className="pretty_container six columns",
),
@@ -72,23 +88,83 @@ def generate_first_row():
def generate_fig_row():
- """Generates First Row (Power and Spectrum) Display
+ """Generates Fig Row (N-point and Beam-switch) Display
Returns
-------
- Div Containing First Row Objects
+ Div Containing Fig Row Objects
"""
+ config = {
+ "displaylogo": False,
+ "scrollZoom": True,
+ "modeBarButtonsToAdd": [
+ "togglehover",
+ "togglespikelines",
+ "drawline",
+ "drawopenpath",
+ "drawclosedpath",
+ "drawcircle",
+ "drawrect",
+ "eraseshape",
+ ],
+ }
+
return html.Div(
[
html.Div(
[
dcc.Store(id="npoint_info", storage_type="session"),
html.Div(
- [dcc.Graph(id="npoint-graph")],
+ [dcc.Graph(id="npoint-graph", config=config)],
+ className="pretty_container six columns",
+ ),
+ html.Div(
+ [dcc.Graph(id="bswitch-graph", config=config)],
+ className="pretty_container six columns",
+ ),
+ ],
+ className="flex-display",
+ style={
+ "justify-content": "left",
+ "margin": "5px",
+ },
+ ),
+ ]
+ )
+
+
+def generate_second_fig_row():
+ """Generates Second Fig Row (Waterfall Plot and Cross Scan) Display
+
+ Returns
+ -------
+ Div Containing Second Fig Row Objects
+ """
+ config = {
+ "displaylogo": False,
+ "scrollZoom": True,
+ "modeBarButtonsToAdd": [
+ "togglehover",
+ "togglespikelines",
+ "drawline",
+ "drawopenpath",
+ "drawclosedpath",
+ "drawcircle",
+ "drawrect",
+ "eraseshape",
+ ],
+ }
+ return html.Div(
+ [
+ html.Div(
+ [
+ # dcc.Store(id="npoint_info", storage_type="session"),
+ html.Div(
+ [dcc.Graph(id="waterfall-graph", config=config)],
className="pretty_container six columns",
),
# html.Div(
- # [dcc.Graph(id="beamsswitch-graph")],
+ # [dcc.Graph(id="cross-scan-graph", config= config)],
# className="pretty_container six columns",
# ),
],
@@ -457,7 +533,25 @@ def generate_layout():
html.Div(
[
html.Div(
- [dcc.Graph(id="az-el-graph")],
+ [
+ dcc.Graph(
+ id="az-el-graph",
+ config={
+ "displaylogo": False,
+ "scrollZoom": True,
+ "modeBarButtonsToAdd": [
+ "togglehover",
+ "togglespikelines",
+ "drawline",
+ "drawopenpath",
+ "drawclosedpath",
+ "drawcircle",
+ "drawrect",
+ "eraseshape",
+ ],
+ },
+ )
+ ],
className="pretty_container twelve columns",
),
],
@@ -465,6 +559,7 @@ def generate_layout():
style={"margin": dict(l=10, r=5, t=5, b=5)},
),
generate_fig_row(),
+ generate_second_fig_row(),
generate_popups(),
html.Div(id="signal", style={"display": "none"}),
]
@@ -501,11 +596,13 @@ def register_callbacks(
Output("cal-spectrum-histogram", "figure"),
[Input("interval-component", "n_intervals")],
)
- def update_cal_spectrum_histogram(n):
+ def update_cal_spectrum_histogram(_):
spectrum = cal_spectrum_thread.get_spectrum()
status = status_thread.get_status()
if status is None or spectrum is None:
- return ""
+ return emptygraph(
+ "Frequency", "Temperature (K)", title="Calibrated Spectrum", height=150
+ )
bandwidth = float(status["bandwidth"])
cf = float(status["center_frequency"])
return generate_spectrum_graph(bandwidth, cf, spectrum, is_spec_cal=True)
@@ -514,12 +611,13 @@ def update_cal_spectrum_histogram(n):
Output("raw-spectrum-histogram", "figure"),
[Input("interval-component", "n_intervals")],
)
- def update_raw_spectrum_histogram(n):
-
+ def update_raw_spectrum_histogram(_):
spectrum = raw_spectrum_thread.get_spectrum()
status = status_thread.get_status()
if status is None or spectrum is None:
- return ""
+ return emptygraph(
+ "Frequency", "Temp. (Unitless)", title="Raw Spectrum", height=150
+ )
bandwidth = float(status["bandwidth"])
cf = float(status["center_frequency"])
return generate_spectrum_graph(bandwidth, cf, spectrum, is_spec_cal=False)
@@ -527,23 +625,49 @@ def update_raw_spectrum_histogram(n):
@app.callback(
Output("power-graph", "figure"), [Input("interval-component", "n_intervals")]
)
- def update_power_graph(n):
+ def update_power_graph(_):
status = status_thread.get_status()
if status is None:
- return ""
+ return emptygraph(
+ "Time", "Calibrated Power", title="Power vs Time", height=300
+ )
tsys = float(status["temp_sys"])
tcal = float(status["temp_cal"])
cal_pwr = float(status["cal_power"])
spectrum_history = raw_spectrum_thread.get_history()
if spectrum_history is None:
- return ""
- return generate_power_history_graph(tsys, tcal, cal_pwr, spectrum_history)
+ return emptygraph(
+ "Time", "Calibrated Power", title="Power vs Time", height=300
+ )
+ gui_timezone = status["gui_timezone"]
+ return generate_power_history_graph(
+ tsys, tcal, cal_pwr, spectrum_history, gui_timezone
+ )
+
+ @app.callback(
+ Output("waterfall-graph", "figure"),
+ [Input("interval-component", "n_intervals")],
+ )
+ def update_waterfall_graph(_):
+ spectrum_history = raw_spectrum_thread.get_history()
+ status = status_thread.get_status()
+ if (not spectrum_history) or (spectrum_history is None) or (status is None):
+ return emptygraph(
+ "Frequency", "Time", title="Raw Spectrum History", height=300
+ )
+ bandwidth = float(status["bandwidth"])
+ cf = float(status["center_frequency"])
+ waterfall_length = status["waterfall_length"]
+ gui_timezone = status["gui_timezone"]
+ return generate_waterfall_graph(
+ bandwidth, cf, spectrum_history, waterfall_length, gui_timezone
+ )
@app.callback(
Output("npoint_info", "data"),
[Input("interval-component", "n_intervals"), State("npoint_info", "data")],
)
- def npointstore(n, npdata):
+ def npointstore(_, npdata):
"""Update the npoint track info
Parameters
@@ -551,7 +675,7 @@ def npointstore(n, npdata):
n : int
number of Update intervals
npdata : dict
- will hold N- point data.
+ will hold N-point data.
Returns
-------
@@ -595,7 +719,7 @@ def update_n_point(ts, npdata):
ts : int
modified time stamp
npdata : dict
- will hold N- point data.
+ will hold N-point data.
Returns
-------
@@ -606,10 +730,10 @@ def update_n_point(ts, npdata):
if ts is None:
raise PreventUpdate
if npdata is None:
- return emptygraph("x", "y", "N-Point Scan")
+ return emptygraph("x", "y", title="N-Point Scan", height=300)
if npdata.get("scan_center", [1, 1])[0] == 0:
- return emptygraph("x", "y", "N-Point Scan")
+ return emptygraph("x", "y", title="N-Point Scan", height=300)
az_a = []
el_a = []
@@ -623,11 +747,25 @@ def update_n_point(ts, npdata):
ofig = generate_npoint(az_a, el_a, mdiff[0], mdiff[1], plist, sc, sd)
return ofig
+ @app.callback(
+ Output("bswitch-graph", "figure"), [Input("interval-component", "n_intervals")]
+ )
+ def update_bswitch_graph(_):
+ status = status_thread.get_status()
+ if not status:
+ return emptygraph("Position", "Power", title="Beam switch", height=300)
+ power_bswitch_live = status["power_bswitch_live"]
+ if not power_bswitch_live:
+ return emptygraph("Position", "Power", title="Beam switch", height=300)
+ num_beamswitches = status["num_beamswitches"]
+ bswitch_fig = generate_bswitch_graph(power_bswitch_live, num_beamswitches)
+ return bswitch_fig
+
@app.callback(
Output("start-warning", "children"),
[Input("interval-component", "n_intervals")],
)
- def update_start_daemon_warning(n):
+ def update_start_daemon_warning(_):
status = status_thread.get_status()
if status is None:
return "SRT Daemon Not Detected"
@@ -641,7 +779,7 @@ def update_start_daemon_warning(n):
Output("start-config-file", "options"),
[Input("interval-component", "n_intervals")],
)
- def update_start_daemon_options(n):
+ def update_start_daemon_options(_):
files = [
{"label": file.name, "value": file.name}
for file in Path(config["CONFIG_DIR"]).glob("*")
@@ -654,10 +792,11 @@ def update_start_daemon_options(n):
[Input("upload-data", "contents")],
[State("upload-data", "filename"), State("upload-data", "last_modified")],
)
- def update_output(contents, name, date):
+ def update_output(contents, name, _):
if contents is not None:
- content_type, content_string = contents.split(",")
- decoded = base64.b64decode(content_string)
+ # content_type, content_string = contents.split(",")
+ _, content_string = contents.split(",")
+ decoded = b64decode(content_string)
try:
if "txt" in name or "cmd" in name:
# Assume that the user uploaded a txt file
@@ -675,9 +814,11 @@ def update_output(contents, name, date):
@app.callback(
Output("az-el-graph", "figure"), [Input("interval-component", "n_intervals")]
)
- def update_az_el_graph(n):
+ def update_az_el_graph(_):
status = status_thread.get_status()
- if status is not None:
+ if status == None:
+ return emptygraph("Azimuth", "Elevation")
+ else:
return generate_az_el_graph(
status["az_limits"],
status["el_limits"],
@@ -687,8 +828,16 @@ def update_az_el_graph(n):
status["cal_loc"],
status["horizon_points"],
status["beam_width"],
+ status["rotor_loc_npoint_live"],
+ status["motor_cmd_azel"],
+ status["minimal_arrows_distance"],
+ status["npoint_arrows"],
+ status["motor_type"],
+ status["station"],
+ status["display_lim"],
+ status["draw_ecliptic"],
+ status["draw_equator"],
)
- return ""
@app.callback(
Output("az-el-graph-modal", "is_open"),
@@ -910,10 +1059,7 @@ def run_srt_daemon(configuration_dir, configuration_dict):
],
)
def cmd_button_pressed(
- n_clicks_stow,
- n_clicks_stop_record,
- n_clicks_shutdown,
- n_clicks_calibrate,
+ *_,
):
ctx = dash.callback_context
if not ctx.triggered:
diff --git a/srt/dashboard/layouts/navbar.py b/srt/dashboard/layouts/navbar.py
index c6234e3c..45de7cac 100644
--- a/srt/dashboard/layouts/navbar.py
+++ b/srt/dashboard/layouts/navbar.py
@@ -28,7 +28,7 @@ def generate_navbar(dropdowns, title="Commands"):
in_navbar=True,
label=drop_down,
style={"display": "flex", "flexWrap": "wrap"},
- className="m-1",
+ class_name="m-1",
)
for drop_down in dropdowns
],
diff --git a/srt/dashboard/layouts/sidebar.py b/srt/dashboard/layouts/sidebar.py
index 917ee332..5cdb6c20 100644
--- a/srt/dashboard/layouts/sidebar.py
+++ b/srt/dashboard/layouts/sidebar.py
@@ -3,6 +3,7 @@
Functions to Generate Sidebar
"""
+
try:
from dash import html
except: