├── .github
└── workflows
│ ├── python-package.yml
│ ├── python-publish.yml
│ └── winbuild.yml
├── .gitignore
├── .travis.yml
├── LICENSE
├── README.md
├── bin
└── dronecan_gui_tool
├── dronecan_gui_tool
├── __init__.py
├── active_data_type_detector.py
├── am32_rtttl.py
├── icons
│ ├── dronecan_gui_tool.png
│ └── logo.ico
├── main.py
├── panels
│ ├── RTK_panel.py
│ ├── RemoteID_panel.py
│ ├── __init__.py
│ ├── actuator_panel.py
│ ├── esc_panel.py
│ ├── hobbywing_esc.py
│ ├── rc_panel.py
│ ├── rtcm3.py
│ ├── serial_panel.py
│ └── stats_panel.py
├── setup_window.py
├── version.py
└── widgets
│ ├── __init__.py
│ ├── about_window.py
│ ├── bus_monitor
│ ├── __init__.py
│ ├── transfer_decoder.py
│ └── window.py
│ ├── can_adapter_control_panel
│ ├── __init__.py
│ └── slcan_cli.py
│ ├── console.py
│ ├── directory_selection.py
│ ├── dynamic_node_id_allocator.py
│ ├── file_server.py
│ ├── local_node.py
│ ├── log_message_display.py
│ ├── node_monitor.py
│ ├── node_properties.py
│ ├── plotter
│ ├── __init__.py
│ ├── plot_areas
│ │ ├── __init__.py
│ │ ├── xy.py
│ │ └── yt.py
│ ├── plot_container.py
│ ├── value_extractor.py
│ ├── value_extractor_views.py
│ └── window.py
│ ├── subscriber.py
│ └── table_display.py
├── icons
└── logo.ico
├── pip_sizes.py
├── pyproject.toml
├── remove_build_outputs.sh
├── screenshot.png
├── setup.py
└── winbuild.bat
/.github/workflows/python-package.yml:
--------------------------------------------------------------------------------
1 | # This workflow will install Python dependencies, run tests and lint with a variety of Python versions
2 | # For more information see: https://help.github.com/actions/language-and-framework-guides/using-python-with-github-actions
3 |
4 | name: Python package
5 |
6 | on:
7 | push:
8 | branches: [ master ]
9 | pull_request:
10 | branches: [ master ]
11 |
12 | jobs:
13 | build:
14 |
15 | runs-on: ubuntu-latest
16 | strategy:
17 | fail-fast: false
18 | matrix:
19 | python-version: ["3.9", "3.10", "3.11"]
20 |
21 | steps:
22 | - uses: actions/checkout@v2
23 | - name: Set up Python ${{ matrix.python-version }}
24 | uses: actions/setup-python@v2
25 | with:
26 | python-version: ${{ matrix.python-version }}
27 | - name: Install dependencies
28 | run: |
29 | python -m pip install -U pip
30 | python -m pip install -U flake8 pytest wheel
31 | python -m pip install -U .
32 | if [ -f requirements.txt ]; then pip install -r requirements.txt; fi
33 |
--------------------------------------------------------------------------------
/.github/workflows/python-publish.yml:
--------------------------------------------------------------------------------
1 | # This workflow will upload a Python Package using Twine when a release is created
2 | # For more information see: https://help.github.com/en/actions/language-and-framework-guides/using-python-with-github-actions#publishing-to-package-registries
3 |
4 | # This workflow uses actions that are not certified by GitHub.
5 | # They are provided by a third-party and are governed by
6 | # separate terms of service, privacy policy, and support
7 | # documentation.
8 |
9 | name: Upload Python Package
10 |
11 | on:
12 | release:
13 | types: [published]
14 |
15 | jobs:
16 | deploy:
17 |
18 | runs-on: ubuntu-latest
19 |
20 | steps:
21 | - uses: actions/checkout@v2
22 | - name: Set up Python
23 | uses: actions/setup-python@v2
24 | with:
25 | python-version: '3.10'
26 | - name: Install dependencies
27 | run: |
28 | python -m pip install --upgrade pip
29 | pip install build
30 | python -m pip install -U flake8 pytest wheel
31 | python -m pip install -U .
32 | - name: Build package
33 | run: python -m build
34 | - name: Publish package
35 | uses: pypa/gh-action-pypi-publish@release/v1
36 | with:
37 | user: __token__
38 | password: ${{ secrets.PYPI_API_TOKEN }}
39 |
--------------------------------------------------------------------------------
/.github/workflows/winbuild.yml:
--------------------------------------------------------------------------------
1 | # This continuous integration pipeline is triggered anytime a user pushes code to the repo.
2 | # This pipeline builds the Wpf project, runs unit tests, then saves the MSIX build artifact.
3 | name: Windows CI
4 |
5 | # Trigger on every master branch push and pull request
6 | on:
7 | push:
8 | branches:
9 | - '*'
10 | pull_request:
11 | branches:
12 | - '*'
13 |
14 | jobs:
15 |
16 | build:
17 |
18 | strategy:
19 | matrix:
20 | targetplatform: [x64]
21 |
22 | runs-on: windows-latest
23 |
24 |
25 | steps:
26 | - name: Checkout
27 | uses: actions/checkout@v2
28 | with:
29 | fetch-depth: 0 # avoid shallow clone so nbgv can do its work.
30 |
31 |
32 | - uses: actions/setup-python@v2
33 | with:
34 | python-version: '3.10'
35 |
36 |
37 | # Build the Windows Application Packaging project
38 | - name: Build a Windows App
39 | shell: cmd
40 | run: .\winbuild.bat
41 |
42 | # Upload the MSIX package: https://github.com/marketplace/actions/upload-artifact
43 | - name: Upload build artifacts
44 | uses: actions/upload-artifact@v4
45 | with:
46 | name: MSI Package
47 | path: dist
48 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | # Byte-compiled / optimized / DLL files
2 | __pycache__/
3 | *.py[cod]
4 | *$py.class
5 |
6 | # C extensions
7 | *.so
8 |
9 | # Distribution / packaging
10 | .Python
11 | env/
12 | build/
13 | develop-eggs/
14 | dist/
15 | downloads/
16 | eggs/
17 | .eggs/
18 | lib/
19 | lib64/
20 | parts/
21 | sdist/
22 | var/
23 | *.egg-info/
24 | .installed.cfg
25 | *.egg
26 |
27 | # PyInstaller
28 | # Usually these files are written by a python script from a template
29 | # before PyInstaller builds the exe, so as to inject date/other infos into it.
30 | *.manifest
31 | *.spec
32 |
33 | # Installer logs
34 | pip-log.txt
35 | pip-delete-this-directory.txt
36 |
37 | # Unit test / coverage reports
38 | htmlcov/
39 | .tox/
40 | .coverage
41 | .coverage.*
42 | .cache
43 | nosetests.xml
44 | coverage.xml
45 | *,cover
46 | .hypothesis/
47 |
48 | # Translations
49 | *.mo
50 | *.pot
51 |
52 | # Django stuff:
53 | *.log
54 |
55 | # Sphinx documentation
56 | docs/_build/
57 |
58 | # PyBuilder
59 | target/
60 |
61 | #Ipython Notebook
62 | .ipynb_checkpoints
63 |
64 | # IDE
65 | .idea/
66 |
67 | venv/
68 |
--------------------------------------------------------------------------------
/.travis.yml:
--------------------------------------------------------------------------------
1 | sudo: false
2 | language: python
3 | python:
4 | - '3.5'
5 | install: pip3 install .
6 | script: echo Doing nothing
7 | deploy:
8 | provider: pypi
9 | username: __token__
10 | password:
11 | secure: oX7kxpjb/C1PjeYl3kUWoynCjE7XvcR6nlvXHtRv4X9Jja8EIS4SgYxb1+d6yYI5eCDhyC6q5eMwFVcaAGOw6THnZ3Nx6saYBZf91fdSMWOhvOfqrsS7SkK7WEa2+XO9t7fBDZ3/kPo+3N6Aowv3tG7NUo30n+3qx2CfaJN60mNRCmoQjlUi34M19macOClAJ592PsZQIKZUX6aHvjwdNDbGq8qmkMCV/6P7wWlA0RezwematVVevzV72tncch5KPPPPXaSXbranQG+KM+SKR8ry0i+W+5HS+9oD94KhhLuzIXi+ZlKvLW7Ijg/KETalQWvYAREx9Ud05fscIcPOMx2TAuGGUyqmPX5W5xL5mQemTnnmGsWz5QPnfpB44CjTDRvhfUhHRAaNsi+e1AaKVOFBZClNCIEt6TJivrDhLT9zruDb6KGfari94S1jxQilHCG2pJb+wiOLjn/NXYtsxFZH02gSxRVs1NaNSHyFHZYmrlgZ6CikLzYMPliES8rTnH4CIDg/3HvHbOK+44TGtHyQhL6da4OAzl0xWEJksYbJ4Kk8anCIMl9qEmMJbLzGPGYUvbmsSRe9SICG44+bzoGlyBUpzgcUbOL83X5JU5Bor4iHyCk7u2xwGOhZjtzKgX4/NOsf9j157JB5AEfyvnjutVYqKFJ3Ffonrrqr6kU=
12 | on:
13 | tags: true
14 | repo: DroneCAN/gui_tool
15 | distributions: bdist_wheel
16 | skip_cleanup: true
17 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | The MIT License (MIT)
2 |
3 | Copyright (c) 2016 UAVCAN
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | DroneCAN GUI Tool
2 | =======================
3 |
4 | DroneCAN GUI Tool is a cross-platform (Windows/Linux/OSX) application for UAVCAN v0.9 and/or DroneCAN V1 management and diagnostics.
5 |
6 | [Read the docs at **https://dronecan.org**](https://dronecan.org).
7 |
8 | [Ask questions at **https://ardupilot.org/copter/docs/common-contact-us.html**](https://ardupilot.org/copter/docs/common-contact-us.html).
9 |
10 | Read installation instructions:
11 |
12 | - [**GNU/LINUX**](#installing-on-gnulinux)
13 | - [**WINDOWS**](#installing-on-windows)
14 | - [**MACOS**](#installing-on-macos)
15 |
16 | 
17 |
18 | ## Installing on GNU/Linux
19 |
20 | The general approach is simple:
21 |
22 | 1. Install PyQt5 for Python 3 using your OS' package manager (e.g. APT).
23 | 2. Install the application itself from Git via PIP:
24 | `pip3 install git+https://github.com/DroneCAN/gui_tool@master`
25 | (it is not necessary to clone this repository manually).
26 | Alternatively, if you're a developer and you want to install your local copy, use `pip3 install .`.
27 |
28 | It also may be necessary to install additional dependencies, depending on your distribution (see details below).
29 |
30 | Once the application is installed, you should see new desktop entries available in your desktop menu;
31 | also a new executable `dronecan_gui_tool` will be available in your `PATH`.
32 | If your desktop environment doesn't update the menu automatically, you may want to do it manually, e.g.
33 | by invoking `sudo update-desktop-database` (command depends on the distribution).
34 |
35 | It is also recommended to install Matplotlib - it is not used by the application itself,
36 | but it may come in handy when using the embedded IPython console.
37 |
38 | ### Debian-based distributions
39 |
40 | ```bash
41 | sudo apt-get install -y python3-pip python3-setuptools python3-wheel
42 | sudo apt-get install -y python3-numpy python3-pyqt5 python3-pyqt5.qtsvg git-core
43 | python3 -m pip install git+https://github.com/DroneCAN/gui_tool@master
44 | ```
45 |
46 | #### Troubleshooting
47 |
48 | If installation fails with an error like below, try to install IPython directly with `python3 -m pip install ipython`:
49 |
50 | > error: Setup script exited with error in ipython setup command:
51 | > Invalid environment marker: sys_platform == "darwin" and platform_python_implementation == "CPython"
52 |
53 | If you're still unable to install the package, please open a ticket.
54 |
55 | ### RPM-based distributions
56 |
57 | *Maintainers wanted*
58 |
59 | #### Fedora 29+
60 | ```bash
61 | sudo dnf install python3-PyQt5
62 | python3 -m pip install git+https://github.com/DroneCAN/gui_tool@master
63 | ```
64 |
65 | ## Installing on Windows
66 |
67 | In order to install this application,
68 | **download and install the latest `.msi` package from here: **.
69 |
70 | ### Building the MSI package
71 |
72 | Please see the file winbuild.bat in this directory, or use the MSI file build by github actions on any commit
73 |
74 | ## Installing on macOS
75 |
76 | OSX support is a bit lacking in the way that installation doesn't create an entry in the applications menu,
77 | but this issue should be fixed someday in the future.
78 | Other than that, everything appears to function more or less correctly.
79 | If you have a choice, it is recommended to use Linux or Windows instead,
80 | as these ports are supported much better at the moment.
81 |
82 | ### Homebrew option
83 |
84 | * Install the Homebrew package manager for OSX.
85 | * Run the following commands:
86 |
87 | ```bash
88 | brew install python3
89 | brew postinstall python3
90 | pip3 install PyQt5
91 | pip3 install git+https://github.com/DroneCAN/gui_tool@master
92 | dronecan_gui_tool
93 | ```
94 |
95 | ### MacPorts option
96 |
97 | Install XCode from App Store, install MacPorts from ,
98 | then run the commands below.
99 | If you're prompted to install Command Line Developer Tools, agree.
100 |
101 | ```bash
102 | sudo port selfupdate
103 | sudo port install curl-ca-bundle py35-pip py35-pyqt5 py35-numpy
104 | python3.5 -m pip install git+https://github.com/DroneCAN/gui_tool@master
105 | ```
106 |
107 | We would like to provide prebuilt application packages instead of the mess above.
108 | Contributions adding this capability would be welcome.
109 |
110 | ## Development
111 |
112 | ### Releasing new version
113 |
114 | First, deploy the new version to PyPI. In order to do that, perform the following steps:
115 |
116 | 1. Update the version tuple in `version.py`, e.g. `1, 0`, and commit this change.
117 | 2. Create a new tag with the same version number as in the version file, e.g. `git tag -a 1.0 -m v1.0`.
118 | 3. Push to master: `git push && git push --tags`
119 |
120 | Then, build a Windows MSI package using the instructions above, and upload the resulting MSI to
121 | the distribution server.
122 |
123 | ### Code style
124 |
125 | Please follow the existing code styles .
126 |
127 | ## History
128 |
129 | Much of the development of this tool is based upon original work by
130 | Pavel Kirienko and others from the UAVCAN Development Team. See
131 | https://github.com/UAVCAN/gui_tool for contributors.
132 |
133 |
--------------------------------------------------------------------------------
/bin/dronecan_gui_tool:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 | #
3 | # Copyright (C) 2016 UAVCAN Development Team
4 | #
5 | # This software is distributed under the terms of the MIT License.
6 | #
7 | # Author: Pavel Kirienko
8 | #
9 |
10 | import os
11 | import sys
12 | import multiprocessing
13 |
14 | #
15 | # When frozen, stdout/stderr are None, causing nasty exceptions. This workaround silences them.
16 | #
17 | class SupermassiveBlackHole:
18 | def write(self, *_):
19 | pass
20 |
21 | def read(self, *_):
22 | pass
23 |
24 | def flush(self):
25 | pass
26 |
27 | def close(self):
28 | pass
29 | try:
30 | sys.stdout.flush()
31 | sys.stderr.flush()
32 | except AttributeError:
33 | sys.__stdout__ = sys.stdout = SupermassiveBlackHole()
34 | sys.__stderr__ = sys.stderr = SupermassiveBlackHole()
35 | sys.__stdin__ = sys.stdin = SupermassiveBlackHole()
36 |
37 | #
38 | # This shim enables us to run directly from the source directory not having the package installed.
39 | #
40 | try:
41 | directory = os.path.dirname(os.path.abspath(__file__))
42 | if 'gui_tool' in directory:
43 | print('Running from the source directory')
44 | for dirpath, dirnames, filenames in os.walk(os.path.join(directory, '..')):
45 | for d in dirnames:
46 | if '.' not in d and 'bin' not in d:
47 | sys.path.insert(0, os.path.abspath(os.path.join(directory, '..', d)))
48 | break
49 | sys.path.insert(0, os.path.abspath(os.path.join(directory, '..')))
50 | except NameError:
51 | pass # Seems like we're running in cx_Freeze environment
52 |
53 | #
54 | # Calling main directly.
55 | # The 'if' wrapper is absolutely needed because we're spawning new processes with 'multiprocessing'; refer
56 | # to the Python docs for more info.
57 | #
58 | if __name__ == '__main__':
59 | multiprocessing.freeze_support()
60 | from dronecan_gui_tool.main import main
61 | main()
62 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/dronecan/gui_tool/bbab5bdb80f46aeae720259850d8cace1d27586f/dronecan_gui_tool/__init__.py
--------------------------------------------------------------------------------
/dronecan_gui_tool/active_data_type_detector.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import logging
10 | import dronecan
11 | from PyQt5.QtCore import pyqtSignal, QObject
12 |
13 |
14 | logger = logging.getLogger(__name__)
15 |
16 |
17 | class ActiveDataTypeDetector(QObject):
18 | message_types_updated = pyqtSignal([])
19 | service_types_updated = pyqtSignal([])
20 |
21 | def __init__(self, node):
22 | super(ActiveDataTypeDetector, self).__init__()
23 | self._node = node
24 | self._hook_handle = node.add_transfer_hook(self._on_transfer)
25 | self._active_messages = set()
26 | self._active_services = set()
27 |
28 | def close(self):
29 | self._hook_handle.remove()
30 |
31 | def reset(self):
32 | self._active_messages.clear()
33 | self._active_services.clear()
34 |
35 | def _on_transfer(self, tr):
36 | try:
37 | dtname = dronecan.get_dronecan_data_type(tr.payload).full_name
38 | except Exception:
39 | try:
40 | kind = dronecan.dsdl.CompoundType.KIND_SERVICE if tr.service_not_message else \
41 | dronecan.dsdl.CompoundType.KIND_MESSAGE
42 | dtname = dronecan.DATATYPES[(tr.data_type_id, kind)].full_name
43 | except Exception:
44 | logger.error('Could not detect data type name from transfer %r', tr, exc_info=True)
45 | return
46 |
47 | if tr.service_not_message:
48 | if dtname not in self._active_services:
49 | self._active_services.add(dtname)
50 | self.service_types_updated.emit()
51 | else:
52 | if dtname not in self._active_messages:
53 | self._active_messages.add(dtname)
54 | self.message_types_updated.emit()
55 |
56 | def get_names_of_active_messages(self):
57 | return list(sorted(self._active_messages))
58 |
59 | def get_names_of_active_services(self):
60 | return list(sorted(self._active_services))
61 |
62 | @staticmethod
63 | def get_names_of_all_message_types_with_data_type_id():
64 | message_types = []
65 | for (dtid, kind), dtype in dronecan.DATATYPES.items():
66 | if dtid is not None and kind == dronecan.dsdl.CompoundType.KIND_MESSAGE:
67 | message_types.append(str(dtype))
68 | return list(sorted(message_types))
69 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/icons/dronecan_gui_tool.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/dronecan/gui_tool/bbab5bdb80f46aeae720259850d8cace1d27586f/dronecan_gui_tool/icons/dronecan_gui_tool.png
--------------------------------------------------------------------------------
/dronecan_gui_tool/icons/logo.ico:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/dronecan/gui_tool/bbab5bdb80f46aeae720259850d8cace1d27586f/dronecan_gui_tool/icons/logo.ico
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/RTK_panel.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2023 DroneCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Andrew Tridgell
7 | #
8 |
9 | import dronecan
10 | from functools import partial
11 | from PyQt5.QtWidgets import QGridLayout, QWidget, QLabel, QDialog, \
12 | QVBoxLayout, QGroupBox
13 | from PyQt5.QtCore import Qt, QTimer
14 | from ..widgets import get_icon
15 | from ..widgets import table_display
16 | from . import rtcm3
17 | import time
18 |
19 | __all__ = 'PANEL_NAME', 'spawn', 'get_icon'
20 |
21 | PANEL_NAME = 'RTK Panel'
22 |
23 | _singleton = None
24 |
25 | class RTCMData:
26 | def __init__(self):
27 | self.last_time = {}
28 | self.dt = {}
29 | self.decoder = rtcm3.RTCM3()
30 | self.table = table_display.TableDisplay(['Node','RTCM_ID','Len','Rate(Hz)'])
31 |
32 | def handle_msg(self, msg):
33 | nodeid = msg.transfer.source_node_id
34 | tstamp = msg.transfer.ts_real
35 | data = msg.message.data.to_bytes()
36 | for b in data:
37 | if not self.decoder.read(chr(b)):
38 | continue
39 | pkt_id = self.decoder.get_packet_ID()
40 | pkt_len = len(self.decoder.get_packet())
41 | key = (pkt_id,pkt_len)
42 | if not key in self.last_time:
43 | self.last_time[key] = tstamp
44 |
45 | self.dt[key] = 0.2
46 | dt = tstamp - self.last_time[key]
47 | self.last_time[key] = tstamp
48 | self.dt[key] = 0.9 * self.dt[key] + 0.1 * dt
49 | rate_str = "%.1f" % (1.0/self.dt[key])
50 |
51 | self.table.update(key, [nodeid, pkt_id, pkt_len, rate_str])
52 |
53 |
54 | # mapping of Fix2 status, mode and sub_mode to fix string
55 | fix_status = {
56 | (0,0,0) : "None (0)",
57 | (1,0,0) : "NoFix (1)",
58 | (2,0,0) : "2D (2)",
59 | (3,0,0) : "3D (3)",
60 | (3,1,1) : "3D SBAS (4)",
61 | (3,2,0) : "RTK Float (5)",
62 | (3,2,1) : "RTK Fixed (6)",
63 | }
64 |
65 | class RTKPanel(QDialog):
66 | def __init__(self, parent, node):
67 | super(RTKPanel, self).__init__(parent)
68 | self.setWindowTitle('RTK Information Panel')
69 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
70 |
71 | layout = QVBoxLayout()
72 |
73 | # Fix2 display
74 | self.fix2_table = table_display.TableDisplay(['Node','Status','NumSats', 'Rate(Hz)'])
75 | self.fix2_last_time = {}
76 | self.fix2_dt = {}
77 |
78 | fix2_group = QGroupBox('Fix2 Status', self)
79 | fix2_layout = QGridLayout()
80 | fix2_layout.addWidget(self.fix2_table)
81 | fix2_group.setLayout(fix2_layout)
82 | fix2_group.setToolTip('''
83 | The Fix2 message give the fix status of each GPS.
84 | For RTK moving baseline the rover should be 'RTK Fixed (6)' when operating correctly.
85 | ''')
86 |
87 | # MovingBaseline Display
88 | self.mb = RTCMData()
89 | mb_group = QGroupBox('MovingBaseline Data', self)
90 | mb_layout = QGridLayout()
91 | mb_layout.addWidget(self.mb.table)
92 | mb_group.setLayout(mb_layout)
93 | mb_group.setToolTip('''
94 | The MovingBaseline message provide correction data from a moving baseline base GPS to
95 | a moving baseline rover GPS in order to achieve a relative RTK fix which allows the calculation
96 | of a GPS yaw value
97 | ''')
98 |
99 | # RTCM Display
100 | self.rtcm = RTCMData()
101 | rtcm_group = QGroupBox('RTCMStream Data', self)
102 | rtcm_layout = QGridLayout()
103 | rtcm_layout.addWidget(self.rtcm.table)
104 | rtcm_group.setLayout(rtcm_layout)
105 | rtcm_group.setToolTip('''
106 | The RTCMStream message provide correction data from a ground station to a GPS to allow
107 | it to get a global RTK fix.
108 | ''')
109 |
110 | self.relpos_table = table_display.TableDisplay(['Node','RelHeading','Dist(m)','RelDown(m)','Rate(Hz)'])
111 | self.relpos_last_time = {}
112 | self.relpos_dt = {}
113 |
114 | relpos_group = QGroupBox('RelPosHeading Status', self)
115 | relpos_layout = QGridLayout()
116 | relpos_layout.addWidget(self.relpos_table)
117 | relpos_group.setLayout(relpos_layout)
118 | relpos_group.setToolTip('''
119 | The RelPosHeading message provides information on the relative position of the two GPS modules.
120 | The distance should match the actual distance between the antennas.
121 | ''')
122 |
123 | layout.addWidget(fix2_group)
124 | layout.addWidget(mb_group)
125 | layout.addWidget(rtcm_group)
126 | layout.addWidget(relpos_group)
127 | self.setLayout(layout)
128 | self.resize(self.minimumWidth(), self.minimumHeight())
129 |
130 | self.handlers = [node.add_handler(dronecan.uavcan.equipment.gnss.Fix2, self.handle_Fix2),
131 | node.add_handler(dronecan.ardupilot.gnss.MovingBaselineData, self.handle_RTCM_MovingBase),
132 | node.add_handler(dronecan.uavcan.equipment.gnss.RTCMStream, self.handle_RTCM_Stream),
133 | node.add_handler(dronecan.ardupilot.gnss.RelPosHeading, self.handle_RelPos)]
134 |
135 | def handle_Fix2(self, msg):
136 | '''display Fix2 data in table'''
137 | nodeid = msg.transfer.source_node_id
138 | tstamp = msg.transfer.ts_real
139 | if not nodeid in self.fix2_last_time:
140 | self.fix2_last_time[nodeid] = tstamp
141 | self.fix2_dt[nodeid] = 0.2
142 | dt = tstamp - self.fix2_last_time[nodeid]
143 | self.fix2_dt[nodeid] = 0.9 * self.fix2_dt[nodeid] + 0.1 * dt
144 | self.fix2_last_time[nodeid] = tstamp
145 |
146 | status_key = (msg.message.status, msg.message.mode, msg.message.sub_mode)
147 | status_str = fix_status.get(status_key, str(status_key))
148 | rate_str = "%.1f" % (1.0 / self.fix2_dt[nodeid])
149 | self.fix2_table.update(nodeid, [nodeid, status_str, msg.message.sats_used, rate_str])
150 | #print(nodeid, dronecan.to_yaml(msg))
151 |
152 | def handle_RTCM_MovingBase(self, msg):
153 | '''display RTCM MovingBaseline data in table'''
154 | self.mb.handle_msg(msg)
155 |
156 | def handle_RTCM_Stream(self, msg):
157 | '''display RTCMStream data in table'''
158 | self.rtcm.handle_msg(msg)
159 |
160 | def handle_RelPos(self, msg):
161 | '''display RelPos data in table'''
162 | nodeid = msg.transfer.source_node_id
163 | tstamp = msg.transfer.ts_real
164 | if nodeid not in self.relpos_last_time:
165 | self.relpos_last_time[nodeid] = tstamp
166 | self.relpos_dt[nodeid] = 0.2
167 | dt = tstamp - self.relpos_last_time[nodeid]
168 | self.relpos_dt[nodeid] = 0.9 * self.relpos_dt[nodeid] + 0.1 * dt
169 | self.relpos_last_time[nodeid] = tstamp
170 |
171 | rate_str = "%.1f" % (1.0 / self.relpos_dt[nodeid])
172 | self.relpos_table.update(nodeid, [nodeid,
173 | "%.1f" % msg.message.reported_heading_deg,
174 | "%.2f" % msg.message.relative_distance_m,
175 | "%.2f" % msg.message.relative_down_pos_m,
176 | rate_str])
177 |
178 |
179 | def __del__(self):
180 | for h in self.handlers:
181 | h.remove()
182 | global _singleton
183 | _singleton = None
184 |
185 | def closeEvent(self, event):
186 | super(RTKPanel, self).closeEvent(event)
187 | self.__del__()
188 |
189 | def spawn(parent, node):
190 | global _singleton
191 | if _singleton is None:
192 | try:
193 | _singleton = RTKPanel(parent, node)
194 | except Exception as ex:
195 | print(ex)
196 |
197 | _singleton.show()
198 | _singleton.raise_()
199 | _singleton.activateWindow()
200 |
201 | return _singleton
202 |
203 | get_icon = partial(get_icon, 'fa6s.asterisk')
204 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/RemoteID_panel.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2023 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Andrew Tridgell
7 | #
8 |
9 | import dronecan
10 | from functools import partial
11 | from PyQt5.QtWidgets import QVBoxLayout, QWidget, QLabel, QDialog, \
12 | QPlainTextEdit, QPushButton, QLineEdit, QFileDialog, QComboBox, QHBoxLayout
13 | from PyQt5.QtCore import QTimer, Qt
14 | from logging import getLogger
15 | from ..widgets import make_icon_button, get_icon, get_monospace_font, directory_selection
16 | import random
17 | import base64
18 | import struct
19 |
20 | __all__ = 'PANEL_NAME', 'spawn', 'get_icon'
21 |
22 | PANEL_NAME = 'RemoteID Panel'
23 |
24 | logger = getLogger(__name__)
25 |
26 | _singleton = None
27 |
28 | SECURE_COMMAND_GET_REMOTEID_SESSION_KEY = dronecan.dronecan.remoteid.SecureCommand.Request().SECURE_COMMAND_GET_REMOTEID_SESSION_KEY
29 | SECURE_COMMAND_SET_REMOTEID_CONFIG = dronecan.dronecan.remoteid.SecureCommand.Request().SECURE_COMMAND_SET_REMOTEID_CONFIG
30 |
31 | class RemoteIDPanel(QDialog):
32 | DEFAULT_INTERVAL = 0.1
33 |
34 | def __init__(self, parent, node):
35 | super(RemoteIDPanel, self).__init__(parent)
36 | self.setWindowTitle('RemoteID Management Panel')
37 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
38 |
39 | self.timeout = 5
40 |
41 | self._node = node
42 | self.session_key = None
43 | self.sequence = random.randint(0, 0xFFFFFFFF)
44 |
45 | layout = QVBoxLayout()
46 |
47 | self.key_selection = directory_selection.DirectorySelectionWidget(self, 'Secret key file')
48 | self.command = QLineEdit(self)
49 | self.send = QPushButton('Send', self)
50 | self.send.clicked.connect(self.on_send)
51 |
52 | self.node_select = QComboBox()
53 |
54 | self.state = QLineEdit()
55 | self.state.setText("")
56 | self.state.setReadOnly(True)
57 |
58 | layout.addLayout(self.labelWidget('Node', self.node_select))
59 | layout.addWidget(self.key_selection)
60 | layout.addLayout(self.labelWidget('Command:', self.command))
61 | layout.addLayout(self.labelWidget('Status:', self.state))
62 | layout.addWidget(self.send)
63 |
64 | self.setLayout(layout)
65 | self.resize(400, 200)
66 | QTimer.singleShot(250, self.update_nodes)
67 |
68 |
69 | def labelWidget(self, label, widget):
70 | '''a widget with a label'''
71 | hlayout = QHBoxLayout()
72 | hlayout.addWidget(QLabel(label, self))
73 | hlayout.addWidget(widget)
74 | return hlayout
75 |
76 | def on_send(self):
77 | '''callback for send button'''
78 | priv_key = self.key_selection.get_selection()
79 | if priv_key is None:
80 | self.status_update("Need to select private key")
81 | return
82 | self.status_update("Requesting session key")
83 | self.request_session_key()
84 |
85 | def status_update(self, text):
86 | '''update status line'''
87 | self.state.setText(text)
88 |
89 | def update_nodes(self):
90 | '''update list of available nodes'''
91 | QTimer.singleShot(250, self.update_nodes)
92 | from ..widgets.node_monitor import app_node_monitor
93 | if app_node_monitor is None:
94 | return
95 | node_list = []
96 | for nid in app_node_monitor._registry.keys():
97 | r = app_node_monitor._registry[nid]
98 | if r.info is not None:
99 | node_list.append("%u: %s" % (nid, r.info.name.decode()))
100 | else:
101 | node_list.append("%u" % nid)
102 | node_list = sorted(node_list)
103 | current_node = sorted([self.node_select.itemText(i) for i in range(self.node_select.count())])
104 | for n in node_list:
105 | if not n in current_node:
106 | self.node_select.addItem(n)
107 |
108 | def get_session_key_response(self, reply):
109 | '''handle session key response'''
110 | if not reply:
111 | self.status_update("session key timed out")
112 | return
113 | self.session_key = bytearray(reply.response.data)
114 | self.status_update("Got session key")
115 | self.send_config_change()
116 |
117 | def get_private_key(self):
118 | '''get private key, return 32 byte key or None'''
119 | priv_key_file = self.key_selection.get_selection()
120 | if priv_key_file is None:
121 | self.status_update("Please select private key file")
122 | return None
123 | try:
124 | d = open(priv_key_file,'r').read()
125 | except Exception as ex:
126 | print(ex)
127 | return None
128 | ktype = "PRIVATE_KEYV1:"
129 | if not d.startswith(ktype):
130 | return None
131 | return base64.b64decode(d[len(ktype):])
132 |
133 | def make_signature(self, seq, command, data):
134 | '''make a signature'''
135 | import monocypher
136 | private_key = self.get_private_key()
137 | d = struct.pack("
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | from ..widgets import show_error
10 |
11 | # TODO: Load all inner modules automatically. This is not really easy because we have to support freezing.
12 | from . import esc_panel
13 | from . import actuator_panel
14 | from . import RTK_panel
15 | from . import serial_panel
16 | from . import stats_panel
17 | from . import RemoteID_panel
18 | from . import hobbywing_esc
19 | from . import rc_panel
20 |
21 | class PanelDescriptor:
22 | def __init__(self, module):
23 | self.name = module.PANEL_NAME
24 | self._module = module
25 |
26 | def get_icon(self):
27 | # noinspection PyBroadException
28 | try:
29 | return self._module.get_icon()
30 | except Exception:
31 | pass
32 |
33 | def safe_spawn(self, parent, node):
34 | try:
35 | return self._module.spawn(parent, node)
36 | except Exception as ex:
37 | show_error('Panel error', 'Could not spawn panel', ex)
38 |
39 |
40 | PANELS = [
41 | PanelDescriptor(esc_panel),
42 | PanelDescriptor(actuator_panel),
43 | PanelDescriptor(RTK_panel),
44 | PanelDescriptor(serial_panel),
45 | PanelDescriptor(stats_panel),
46 | PanelDescriptor(RemoteID_panel),
47 | PanelDescriptor(hobbywing_esc),
48 | PanelDescriptor(rc_panel)
49 | ]
50 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/actuator_panel.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2021 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Tom Pittenger
7 | #
8 |
9 | import dronecan
10 | from functools import partial
11 | from PyQt5.QtWidgets import QVBoxLayout, QHBoxLayout, QWidget, QLabel, QDialog, QSlider, QSpinBox, QDoubleSpinBox, QCheckBox, \
12 | QPlainTextEdit
13 | from PyQt5.QtCore import QTimer, Qt
14 | from logging import getLogger
15 | from ..widgets import make_icon_button, get_icon, get_monospace_font
16 |
17 | __all__ = 'PANEL_NAME', 'spawn', 'get_icon'
18 |
19 | PANEL_NAME = 'Actuator Panel'
20 |
21 |
22 | logger = getLogger(__name__)
23 |
24 | _singleton = None
25 |
26 |
27 |
28 | class PercentSlider(QWidget):
29 | def __init__(self, parent):
30 | super(PercentSlider, self).__init__(parent)
31 |
32 | self._slider = QSlider(Qt.Vertical, self)
33 | self._slider.setMinimum(-1000)
34 | self._slider.setMaximum(1000)
35 | self._slider.setValue(0)
36 | self._slider.setTickInterval(1000)
37 | self._slider.setTickPosition(QSlider.TicksBothSides)
38 | self._slider.valueChanged.connect(lambda: self._spinbox.setValue(self._slider.value()/1000.0))
39 |
40 | self._spinbox = QDoubleSpinBox(self)
41 | self._spinbox.setMinimum(-1)
42 | self._spinbox.setMaximum(1)
43 | self._spinbox.setValue(0)
44 | self._spinbox.setDecimals(3)
45 | self._spinbox.setSingleStep(0.001)
46 | self._spinbox.valueChanged.connect(lambda: self._slider.setValue(self._spinbox.value()*1000.0))
47 |
48 | self._zero_button = make_icon_button('fa6.hand', 'Zero setpoint', self, text = 'Zero', on_clicked=self.zero)
49 |
50 | self._actuator_id = QSpinBox(self)
51 | self._actuator_id.setMinimum(0)
52 | self._actuator_id.setMaximum(15)
53 | self._actuator_id.setValue(0)
54 | self._actuator_id.setPrefix('ID: ')
55 |
56 | self._enabled = QCheckBox('Enabled', self)
57 | self._enabled.setGeometry(0, 0, 10, 10)
58 |
59 | layout = QVBoxLayout(self)
60 | sub_layout = QHBoxLayout(self)
61 | sub_layout.addStretch()
62 | sub_layout.addWidget(self._slider)
63 | sub_layout.addStretch()
64 | layout.addLayout(sub_layout)
65 | layout.addWidget(self._spinbox)
66 | layout.addWidget(self._zero_button)
67 | layout.addWidget(self._actuator_id)
68 | layout.addWidget(self._enabled)
69 | self.setLayout(layout)
70 |
71 | self.setMinimumHeight(400)
72 |
73 | def zero(self):
74 | self._slider.setValue(0)
75 |
76 | def get_value(self):
77 | return self._spinbox.value()
78 |
79 | def get_actuator_id(self):
80 | return self._actuator_id.value()
81 |
82 | def is_enabled(self):
83 | return self._enabled.isChecked()
84 |
85 |
86 | class ActuatorPanel(QDialog):
87 | DEFAULT_INTERVAL = 0.1
88 |
89 | def __init__(self, parent, node):
90 | super(ActuatorPanel, self).__init__(parent)
91 | self.setWindowTitle('Actuator Management Panel')
92 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
93 |
94 | self._node = node
95 |
96 | self._sliders = [PercentSlider(self) for _ in range(4)]
97 |
98 | self._num_sliders = QSpinBox(self)
99 | self._num_sliders.setMinimum(len(self._sliders))
100 | self._num_sliders.setMaximum(20)
101 | self._num_sliders.setValue(len(self._sliders))
102 | self._num_sliders.valueChanged.connect(self._update_number_of_sliders)
103 |
104 | self._bcast_interval = QDoubleSpinBox(self)
105 | self._bcast_interval.setMinimum(0.01)
106 | self._bcast_interval.setMaximum(9.9)
107 | self._bcast_interval.setSingleStep(0.01)
108 | self._bcast_interval.setValue(self.DEFAULT_INTERVAL)
109 | self._bcast_interval.valueChanged.connect(
110 | lambda: self._bcast_timer.setInterval(self._bcast_interval.value() * 1e3))
111 |
112 | self._stop_all = make_icon_button('fa6.hand', 'Zero all channels', self, text='Zero All',
113 | on_clicked=self._do_stop_all)
114 |
115 | self._pause = make_icon_button('fa6s.pause', 'Pause publishing', self, checkable=True, text='Pause')
116 |
117 | self._msg_viewer = QPlainTextEdit(self)
118 | self._msg_viewer.setReadOnly(True)
119 | self._msg_viewer.setLineWrapMode(QPlainTextEdit.NoWrap)
120 | self._msg_viewer.setFont(get_monospace_font())
121 | self._msg_viewer.setVerticalScrollBarPolicy(Qt.ScrollBarAsNeeded)
122 | self._msg_viewer.setHorizontalScrollBarPolicy(Qt.ScrollBarAsNeeded)
123 |
124 | self._bcast_timer = QTimer(self)
125 | self._bcast_timer.start(int(self.DEFAULT_INTERVAL * 1e3))
126 | self._bcast_timer.timeout.connect(self._do_broadcast)
127 |
128 | layout = QVBoxLayout(self)
129 |
130 | self._slider_layout = QHBoxLayout(self)
131 | for sl in self._sliders:
132 | self._slider_layout.addWidget(sl)
133 | layout.addLayout(self._slider_layout)
134 |
135 | layout.addWidget(self._stop_all)
136 |
137 | controls_layout = QHBoxLayout(self)
138 | controls_layout.addWidget(QLabel('Channels:', self))
139 | controls_layout.addWidget(self._num_sliders)
140 | controls_layout.addWidget(QLabel('Broadcast interval:', self))
141 | controls_layout.addWidget(self._bcast_interval)
142 | controls_layout.addWidget(QLabel('sec', self))
143 | controls_layout.addStretch()
144 | controls_layout.addWidget(self._pause)
145 | layout.addLayout(controls_layout)
146 |
147 | layout.addWidget(QLabel('Generated message:', self))
148 | layout.addWidget(self._msg_viewer)
149 |
150 | self.setLayout(layout)
151 | self.resize(self.minimumWidth(), self.minimumHeight())
152 |
153 | def _do_broadcast(self):
154 | try:
155 | if not self._pause.isChecked():
156 | # msg = dronecan.uavcan.equipment.esc.RawCommand()
157 | msg = dronecan.uavcan.equipment.actuator.ArrayCommand()
158 | for sl in self._sliders:
159 | if sl.is_enabled() == False:
160 | continue
161 | msg_cmd = dronecan.uavcan.equipment.actuator.Command()
162 | msg_cmd.actuator_id = sl.get_actuator_id()
163 | msg_cmd.command_value = sl.get_value()
164 | msg_cmd.command_type = 0
165 | msg.commands.append(msg_cmd)
166 |
167 | self._node.broadcast(msg)
168 | self._msg_viewer.setPlainText(dronecan.to_yaml(msg))
169 | else:
170 | self._msg_viewer.setPlainText('Paused')
171 | except Exception as ex:
172 | self._msg_viewer.setPlainText('Publishing failed:\n' + str(ex))
173 |
174 | def _do_stop_all(self):
175 | for sl in self._sliders:
176 | sl.zero()
177 |
178 | def _update_number_of_sliders(self):
179 | num_sliders = self._num_sliders.value()
180 |
181 | while len(self._sliders) > num_sliders:
182 | removee = self._sliders[-1]
183 | self._sliders = self._sliders[:-1]
184 | self._slider_layout.removeWidget(removee)
185 | removee.close()
186 | removee.deleteLater()
187 |
188 | while len(self._sliders) < num_sliders:
189 | new = PercentSlider(self)
190 | self._slider_layout.addWidget(new)
191 | self._sliders.append(new)
192 |
193 | def deferred_resize():
194 | self.resize(self.minimumWidth(), self.height())
195 |
196 | deferred_resize()
197 | # noinspection PyCallByClass,PyTypeChecker
198 | QTimer.singleShot(200, deferred_resize)
199 |
200 | def __del__(self):
201 | global _singleton
202 | _singleton = None
203 |
204 | def closeEvent(self, event):
205 | global _singleton
206 | _singleton = None
207 | super(ActuatorPanel, self).closeEvent(event)
208 |
209 |
210 | def spawn(parent, node):
211 | global _singleton
212 | if _singleton is None:
213 | _singleton = ActuatorPanel(parent, node)
214 |
215 | _singleton.show()
216 | _singleton.raise_()
217 | _singleton.activateWindow()
218 |
219 | return _singleton
220 |
221 |
222 | get_icon = partial(get_icon, 'fa6s.asterisk')
223 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/hobbywing_esc.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2023 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Andrew Tridgell
7 | #
8 |
9 | import dronecan
10 | from functools import partial
11 | from PyQt5.QtWidgets import QVBoxLayout, QWidget, QLabel, QDialog, \
12 | QPlainTextEdit, QPushButton, QLineEdit, QFileDialog, QComboBox, QHBoxLayout, QSpinBox
13 | from PyQt5.QtCore import QTimer, Qt
14 | from logging import getLogger
15 | from ..widgets import make_icon_button, get_icon, get_monospace_font
16 | from ..widgets import table_display
17 | import random
18 | import base64
19 | import struct
20 |
21 | __all__ = 'PANEL_NAME', 'spawn', 'get_icon'
22 |
23 | PANEL_NAME = 'Hobbywing ESC Panel'
24 |
25 | logger = getLogger(__name__)
26 |
27 | _singleton = None
28 |
29 | class HobbywingPanel(QDialog):
30 | DEFAULT_INTERVAL = 0.1
31 |
32 | def __init__(self, parent, node):
33 | super(HobbywingPanel, self).__init__(parent)
34 | self.setWindowTitle('Hobbywing ESC Panel')
35 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
36 |
37 | self._node = node
38 | self.node_map = {}
39 |
40 | layout = QVBoxLayout()
41 |
42 | self.table = table_display.TableDisplay(['Node','ThrottleID','RPM','Voltage','Current','Temperature','Direction'])
43 | layout.addWidget(self.table)
44 |
45 | self.baudrate = QComboBox(self)
46 | for b in [50000, 100000, 200000, 250000, 500000, 1000000]:
47 | self.baudrate.addItem(str(b))
48 | self.baudrate.setCurrentText(str(1000000))
49 | self.baudrate_set = QPushButton('Set', self)
50 | self.baudrate_set.clicked.connect(self.on_baudrate_set)
51 |
52 | layout.addLayout(self.labelWidget('Baudrate:', [self.baudrate, self.baudrate_set]))
53 |
54 | self.throttleid = QSpinBox(self)
55 | self.throttleid.setMinimum(1)
56 | self.throttleid.setMaximum(32)
57 | self.throttleid.setValue(1)
58 | self.throttleid_set = QPushButton('Set', self)
59 | self.throttleid_set.clicked.connect(self.on_throttleid_set)
60 |
61 | layout.addLayout(self.labelWidget('ThrottleID:', [self.throttleid, self.throttleid_set]))
62 |
63 | self.nodeid = QSpinBox(self)
64 | self.nodeid.setMinimum(1)
65 | self.nodeid.setMaximum(127)
66 | self.nodeid.setValue(1)
67 | self.nodeid_set = QPushButton('Set', self)
68 | self.nodeid_set.clicked.connect(self.on_nodeid_set)
69 |
70 | layout.addLayout(self.labelWidget('NodeID:', [self.nodeid, self.nodeid_set]))
71 |
72 | self.direction = QComboBox(self)
73 | self.direction.addItem("CW")
74 | self.direction.addItem("CCW")
75 | self.direction.setCurrentText("CW")
76 | self.direction_set = QPushButton('Set', self)
77 | self.direction_set.clicked.connect(self.on_direction_set)
78 |
79 | layout.addLayout(self.labelWidget('Direction:', [self.direction, self.direction_set]))
80 |
81 | self.msg1rate = QComboBox(self)
82 | for r in [0, 1, 10, 20, 50, 100, 200, 250, 500]:
83 | self.msg1rate.addItem(str(r))
84 | self.msg1rate.setCurrentText("50")
85 | self.msg1rate_set = QPushButton('Set', self)
86 | self.msg1rate_set.clicked.connect(self.on_msg1rate_set)
87 |
88 | layout.addLayout(self.labelWidget('Msg1Rate:', [self.msg1rate, self.msg1rate_set]))
89 |
90 | self.msg2rate = QComboBox(self)
91 | for r in [0, 1, 10, 20, 50, 100, 200, 250, 500]:
92 | self.msg2rate.addItem(str(r))
93 | self.msg2rate.setCurrentText("10")
94 | self.msg2rate_set = QPushButton('Set', self)
95 | self.msg2rate_set.clicked.connect(self.on_msg2rate_set)
96 |
97 | layout.addLayout(self.labelWidget('Msg2Rate:', [self.msg2rate, self.msg2rate_set]))
98 |
99 | self.msg3rate = QComboBox(self)
100 | for r in [0, 1, 10, 20, 50, 100, 200, 250, 500]:
101 | self.msg3rate.addItem(str(r))
102 | self.msg3rate.setCurrentText("10")
103 | self.msg3rate_set = QPushButton('Set', self)
104 | self.msg3rate_set.clicked.connect(self.on_msg3rate_set)
105 |
106 | layout.addLayout(self.labelWidget('Msg3Rate:', [self.msg3rate, self.msg3rate_set]))
107 |
108 | self.throttle_source = QComboBox(self)
109 | self.throttle_source.addItem("---")
110 | self.throttle_source.addItem("PWM")
111 | self.throttle_source.addItem("CAN")
112 | self.throttle_source.setCurrentText("---")
113 | self.throttle_source_set = QPushButton('Set', self)
114 | self.throttle_source_set.clicked.connect(self.on_throttle_source_set)
115 |
116 | layout.addLayout(self.labelWidget('Throttle_source:', [self.throttle_source, self.throttle_source_set]))
117 |
118 | self.setLayout(layout)
119 | self.resize(400, 200)
120 |
121 | self.handlers = [node.add_handler(dronecan.com.hobbywing.esc.StatusMsg1, self.handle_StatusMsg1),
122 | node.add_handler(dronecan.com.hobbywing.esc.StatusMsg2, self.handle_StatusMsg2),
123 | node.add_handler(dronecan.com.hobbywing.esc.GetEscID, self.handle_GetEscID)]
124 |
125 | QTimer.singleShot(500, self.request_ids)
126 |
127 |
128 | def handle_reply(self, msg):
129 | '''handle a reply to a set'''
130 | if msg is not None:
131 | print('REPLY: ', dronecan.to_yaml(msg))
132 | else:
133 | print("No reply")
134 |
135 | def handle_throttle_source_reply(self, msg):
136 | '''handle a reply to a set of throttle source'''
137 | if msg is not None:
138 | print('REPLY: ', dronecan.to_yaml(msg))
139 | else:
140 | print("No reply")
141 |
142 | def handle_GetMajorConfig_reply(self, msg):
143 | '''handle a reply to a GetMajorConfig'''
144 | nodeid = msg.transfer.source_node_id
145 | if msg.response.throttle_source == 0:
146 | txt = "CAN"
147 | else:
148 | txt = "PWM"
149 | if self.throttle_source.currentText() == "---":
150 | self.throttle_source.setCurrentText(txt)
151 |
152 | def on_throttleid_set(self):
153 | '''set throttle ID'''
154 | nodeid = self.table.get_selected()
155 | req = dronecan.com.hobbywing.esc.SetID.Request()
156 | req.node_id = nodeid
157 | req.throttle_channel = int(self.throttleid.value())
158 | self._node.request(req, nodeid, self.handle_reply)
159 |
160 | def on_nodeid_set(self):
161 | '''set node ID'''
162 | nodeid = self.table.get_selected()
163 | thr_id = int(self.table.data[nodeid][1])
164 | req = dronecan.com.hobbywing.esc.SetID.Request()
165 | req.node_id = int(self.nodeid.value())
166 | req.throttle_channel = thr_id
167 | self._node.request(req, nodeid, self.handle_reply)
168 |
169 | def on_baudrate_set(self):
170 | '''set baudrate'''
171 | nodeid = self.table.get_selected()
172 | req = dronecan.com.hobbywing.esc.SetBaud.Request()
173 | bmap = {
174 | 1000000 : req.BAUD_1MBPS,
175 | 500000 : req.BAUD_500KBPS,
176 | 250000 : req.BAUD_250KBPS,
177 | 200000 : req.BAUD_200KBPS,
178 | 100000 : req.BAUD_100KBPS,
179 | 50000 : req.BAUD_50KBPS,
180 | }
181 | baudrate = int(self.baudrate.currentText())
182 | req.baud = bmap[baudrate]
183 | self._node.request(req, nodeid, self.handle_reply)
184 |
185 | def on_direction_set(self):
186 | '''set direction'''
187 | nodeid = self.table.get_selected()
188 | req = dronecan.com.hobbywing.esc.SetDirection.Request()
189 | req.direction = 0 if self.direction.currentText() == "CW" else 1
190 | self._node.request(req, nodeid, self.handle_reply)
191 |
192 | def on_throttle_source_set(self):
193 | '''set throttle source'''
194 | nodeid = self.table.get_selected()
195 | req = dronecan.com.hobbywing.esc.SetThrottleSource.Request()
196 | txt = self.throttle_source.currentText()
197 | if txt == "---":
198 | return
199 | req.source = 0 if txt == "CAN" else 1
200 | self._node.request(req, nodeid, self.handle_throttle_source_reply)
201 |
202 | def set_rate(self, nodeid, msgid, rate):
203 | '''set a message rate'''
204 | req = dronecan.com.hobbywing.esc.SetReportingFrequency.Request()
205 | req.option = req.OPTION_WRITE
206 | req.MSG_ID = msgid
207 | rmap = {
208 | 500 : req.RATE_500HZ,
209 | 250 : req.RATE_250HZ,
210 | 200 : req.RATE_200HZ,
211 | 100 : req.RATE_100HZ,
212 | 50 : req.RATE_50HZ,
213 | 20 : req.RATE_20HZ,
214 | 10 : req.RATE_10HZ,
215 | 1 : req.RATE_1HZ,
216 | }
217 | if not rate in rmap:
218 | print("Invalid rate %d - must be one of %s" % (rate, ','.join(rmap.keys())))
219 | return
220 | req.rate = rmap[rate]
221 | self._node.request(req, nodeid, self.handle_reply)
222 |
223 | def on_msg1rate_set(self):
224 | '''set msg1 rate'''
225 | nodeid = self.table.get_selected()
226 | self.set_rate(nodeid, 20050, int(self.msg1rate.currentText()))
227 |
228 | def on_msg2rate_set(self):
229 | '''set msg2 rate'''
230 | nodeid = self.table.get_selected()
231 | self.set_rate(nodeid, 20051, int(self.msg1rate.currentText()))
232 |
233 | def on_msg3rate_set(self):
234 | '''set msg3 rate'''
235 | nodeid = self.table.get_selected()
236 | self.set_rate(nodeid, 20052, int(self.msg1rate.currentText()))
237 |
238 | def handle_GetEscID(self, msg):
239 | '''handle GetEscID'''
240 | nodeid = msg.transfer.source_node_id
241 | if len(msg.message.payload) != 2:
242 | return
243 | data = self.table.get(nodeid)
244 | if data is None:
245 | data = [nodeid, 0, 0, 0, 0, 0, 0]
246 | self.node_map[nodeid] = msg.message.payload[1]
247 | data[1] = msg.message.payload[1]
248 | self.table.update(nodeid, data)
249 |
250 | def handle_StatusMsg1(self, msg):
251 | '''handle StatusMsg1'''
252 | nodeid = msg.transfer.source_node_id
253 | data = self.table.get(nodeid)
254 | if data is None:
255 | data = [nodeid, 0, 0, 0, 0, 0, 0]
256 | data[6] = "CCW" if msg.message.status & (1<<14) else "CW"
257 | data[2] = msg.message.rpm
258 | self.table.update(nodeid, data)
259 |
260 | def handle_StatusMsg2(self, msg):
261 | '''handle StatusMsg2'''
262 | nodeid = msg.transfer.source_node_id
263 | data = self.table.get(nodeid)
264 | if data is None:
265 | data = [nodeid, 0, 0, 0, 0, 0, 0]
266 | data[3] = "%.2f" % (msg.message.input_voltage*0.1)
267 | data[4] = "%.2f" % (msg.message.current*0.1)
268 | data[5] = msg.message.temperature
269 | self.table.update(nodeid, data)
270 |
271 | def request_ids(self):
272 | '''call GetEscID'''
273 | QTimer.singleShot(500, self.request_ids)
274 | req = dronecan.com.hobbywing.esc.GetEscID()
275 | req.payload = [0]
276 | self._node.broadcast(req)
277 | # for IDs we have, send GetMajorConfig
278 | for nodeid in self.node_map.keys():
279 | req = dronecan.com.hobbywing.esc.GetMajorConfig.Request()
280 | req.option = 0
281 | self._node.request(req, nodeid, self.handle_GetMajorConfig_reply)
282 |
283 |
284 | def labelWidget(self, label, widgets):
285 | '''a widget with a label'''
286 | hlayout = QHBoxLayout()
287 | hlayout.addWidget(QLabel(label, self))
288 | if not isinstance(widgets, list):
289 | widgets = [widgets]
290 | for w in widgets:
291 | hlayout.addWidget(w)
292 | return hlayout
293 |
294 | def __del__(self):
295 | for h in self.handlers:
296 | h.remove()
297 | global _singleton
298 | _singleton = None
299 |
300 | def closeEvent(self, event):
301 | super(HobbywingPanel, self).closeEvent(event)
302 | self.__del__()
303 |
304 |
305 | def spawn(parent, node):
306 | global _singleton
307 | if _singleton is None:
308 | try:
309 | _singleton = HobbywingPanel(parent, node)
310 | except Exception as ex:
311 | print(ex)
312 |
313 | _singleton.show()
314 | _singleton.raise_()
315 | _singleton.activateWindow()
316 |
317 | return _singleton
318 |
319 |
320 | get_icon = partial(get_icon, 'fa6s.asterisk')
321 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/rc_panel.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2023 DroneCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Huibean Luo
7 | #
8 |
9 | import dronecan
10 | from functools import partial
11 | from PyQt5.QtWidgets import QWidget, QLabel, QDialog, \
12 | QVBoxLayout, QHBoxLayout, QSlider, QSpinBox, QPushButton
13 | from PyQt5.QtGui import QPainter, QPen, QColor, QFont
14 | from PyQt5.QtCore import Qt, pyqtSignal, QPointF, QRectF
15 | from PyQt5 import sip
16 | from ..widgets import get_icon
17 |
18 | __all__ = 'PANEL_NAME', 'spawn', 'get_icon'
19 |
20 | PANEL_NAME = 'RC Panel'
21 |
22 | _singleton = None
23 |
24 | STATUS_QUALITY_VALID = 1
25 | STATUS_FAILSAFE = 2
26 |
27 | DRONECAN_MAX_RC_CHANNELS = 32
28 | DEFAULT_DISPLAY_CHANNELS = 16
29 | CHANNEL_CENTER_VALUE = 1500
30 | CHANNEL_VALUE_DISPLAY_RANGE_MAX = 2050
31 | CHANNEL_VALUE_DISPLAY_RANGE_MIN = 950
32 | CHANNEL_VALUE_DISPLAY_RANGE = CHANNEL_VALUE_DISPLAY_RANGE_MAX - CHANNEL_VALUE_DISPLAY_RANGE_MIN
33 |
34 | class ChannelSlider(QSlider):
35 | def __init__(self):
36 | super(ChannelSlider, self).__init__(Qt.Vertical)
37 |
38 | self.setMinimum(CHANNEL_VALUE_DISPLAY_RANGE_MIN)
39 | self.setMaximum(CHANNEL_VALUE_DISPLAY_RANGE_MAX)
40 |
41 | self.min_value = CHANNEL_CENTER_VALUE
42 | self.max_value = CHANNEL_CENTER_VALUE
43 | self.valid = False
44 | self.updateStyleSheet()
45 |
46 | def updateStyleSheet(self):
47 | if self.valid:
48 | self.setStyleSheet("""
49 | QSlider::groove:vertical {
50 | border: 0px solid #999999;
51 | width: 8px;
52 | background: white;
53 | margin: 0 2px;
54 | }
55 | """)
56 | else:
57 | self.setStyleSheet("""
58 | QSlider::groove:vertical {
59 | border: 0px solid #999999;
60 | width: 8px;
61 | background: gray;
62 | margin: 0 2px;
63 | }
64 | """)
65 |
66 | def setValid(self, valid):
67 | self.valid = valid
68 | self.updateStyleSheet()
69 |
70 | def setValue(self, value):
71 | super().setValue(value)
72 | self.min_value = min(self.min_value, value)
73 | self.max_value = max(self.max_value, value)
74 |
75 | def paintEvent(self, event):
76 | super().paintEvent(event)
77 | painter = QPainter(self)
78 |
79 | painter.setBrush(QColor(0, 255, 0))
80 | rect_y0 = self.height() * 0.5
81 | display_value = self.value()
82 | offset = self.height() * 0.5 * (CHANNEL_CENTER_VALUE - display_value) / (CHANNEL_VALUE_DISPLAY_RANGE * 0.5)
83 | rect = QRectF(0, rect_y0, self.width(), offset)
84 | painter.drawRect(rect)
85 |
86 | painter.setPen(Qt.gray)
87 | painter.drawLine(QPointF(0, self.height() *0.5), QPointF(self.width(), self.height() *0.5))
88 |
89 | if self.min_value != CHANNEL_CENTER_VALUE:
90 | painter.setPen(Qt.red)
91 | min_pos = self.height() - abs(self.min_value - CHANNEL_VALUE_DISPLAY_RANGE_MIN) / CHANNEL_VALUE_DISPLAY_RANGE * self.height()
92 | painter.drawLine(QPointF(0, min_pos), QPointF(self.width(), min_pos))
93 |
94 | if self.max_value != CHANNEL_CENTER_VALUE:
95 | painter.setPen(Qt.red)
96 | max_pos = abs(self.max_value - CHANNEL_VALUE_DISPLAY_RANGE_MAX) / CHANNEL_VALUE_DISPLAY_RANGE * self.height()
97 | painter.drawLine(QPointF(0, max_pos), QPointF(self.width(), max_pos))
98 |
99 | class ChannelSliderItem(QWidget):
100 | def __init__(self, ch, parent=None):
101 | super(ChannelSliderItem, self).__init__(parent)
102 |
103 | layout = QVBoxLayout()
104 |
105 | self.ch = ch
106 | self.slider = ChannelSlider()
107 | self.slider.setEnabled(False)
108 | self.slider.setMinimumHeight(60)
109 |
110 | font = QFont()
111 | font.setPointSize(8)
112 |
113 | mini_font = QFont()
114 | mini_font.setPointSize(6)
115 |
116 | self.channel_value_label = QLabel()
117 | self.channel_value_label.setFont(font)
118 |
119 | self.channel_max_value_label = QLabel()
120 | self.channel_max_value_label.setFont(mini_font)
121 |
122 | self.channel_min_value_label = QLabel()
123 | self.channel_min_value_label.setFont(mini_font)
124 |
125 | ch_label = QLabel(f'CH{ch}')
126 | ch_label.setFont(font)
127 |
128 |
129 | layout.addWidget(self.channel_max_value_label)
130 | layout.setAlignment(self.channel_max_value_label, Qt.AlignCenter)
131 |
132 | layout.addWidget(self.slider)
133 | layout.setAlignment(self.slider, Qt.AlignCenter)
134 |
135 | layout.addWidget(self.channel_min_value_label)
136 | layout.setAlignment(self.channel_min_value_label, Qt.AlignCenter)
137 |
138 | layout.addWidget(ch_label)
139 | layout.setAlignment(ch_label, Qt.AlignCenter)
140 |
141 | layout.addWidget(self.channel_value_label)
142 | layout.setAlignment(self.channel_value_label, Qt.AlignCenter)
143 |
144 | layout.addStretch()
145 |
146 | self.setLayout(layout)
147 |
148 | def update_channel_value(self, value):
149 | self.slider.setValue(value)
150 | self.channel_value_label.setText(f'{value}')
151 | self.channel_max_value_label.setText(f'{self.slider.max_value}')
152 | self.channel_min_value_label.setText(f'{self.slider.min_value}')
153 |
154 | def setValid(self, valid):
155 | self.slider.setValid(valid)
156 |
157 | class RcQualityWidget(QWidget):
158 | def __init__(self, parent=None):
159 | super(RcQualityWidget, self).__init__(parent)
160 | self.quality = 0
161 |
162 | def set_quality(self, quality):
163 | self.quality = quality
164 | self.update() # Trigger a repaint
165 |
166 | def paintEvent(self, event):
167 | painter = QPainter(self)
168 |
169 | pen = QPen()
170 | pen.setWidth(1)
171 | pen.setColor(QColor(0, 0, 0))
172 | painter.setPen(pen)
173 |
174 | num_filled = int(self.quality / 255 * 10)
175 |
176 | rect_width = self.width() / 12
177 | rect_height = self.height() - pen.width()
178 | gap = rect_width / 6
179 |
180 | for i in range(10):
181 | if i < num_filled:
182 | painter.setBrush(QColor(0, 255, 0)) # Green for filled rectangles
183 | else:
184 | painter.setBrush(QColor(255, 255, 255)) # white for empty rectangles
185 |
186 | rect = QRectF(i * (rect_width + gap), 0, rect_width, rect_height)
187 | painter.drawRect(rect)
188 |
189 | class RcInfoWidget(QWidget):
190 | def __init__(self, id, parent=None):
191 | super(RcInfoWidget, self).__init__(parent)
192 |
193 | self.setMinimumHeight(160)
194 |
195 | self.id = id
196 | self.status = -1
197 | self.rcin = []
198 |
199 | layout = QVBoxLayout()
200 | info_layout = QHBoxLayout()
201 | info_layout.setContentsMargins(0, 0, 0, 0)
202 | sliders_layout = QHBoxLayout()
203 |
204 | self.id_label = QLabel(f'ID: {self.id} |')
205 | info_layout.addWidget(self.id_label)
206 |
207 | self.status_label = QLabel()
208 | info_layout.addWidget(self.status_label)
209 |
210 | self.channel_num_label = QLabel()
211 | info_layout.addWidget(self.channel_num_label)
212 |
213 | self.quality_label = QLabel()
214 | self.quality_label.setFixedWidth(90)
215 | info_layout.addWidget(self.quality_label)
216 |
217 | self.rc_quality_widget = RcQualityWidget()
218 | self.rc_quality_widget.setFixedWidth(150)
219 | self.rc_quality_widget.setMaximumHeight(20)
220 | info_layout.addWidget(self.rc_quality_widget)
221 |
222 | info_layout.addStretch(1)
223 |
224 | bind_button = QPushButton('Bind')
225 | bind_button.clicked.connect(self.handle_rc_bind)
226 | info_layout.addWidget(bind_button)
227 |
228 | self.sliders = []
229 | self.slider_texts = []
230 | for i in range(DRONECAN_MAX_RC_CHANNELS):
231 | slider = ChannelSliderItem(i+1)
232 | self.sliders.append(slider)
233 | sliders_layout.addWidget(slider)
234 |
235 | layout.addLayout(info_layout)
236 | layout.addLayout(sliders_layout)
237 | self.setLayout(layout)
238 |
239 | def handle_rc_bind(self):
240 | print(f'Bind RC ID: {self.id}')
241 |
242 | def paintEvent(self, event):
243 | painter = QPainter(self)
244 | pen = QPen()
245 | pen.setWidth(1)
246 | pen.setColor(QColor(0, 0, 0))
247 | painter.setPen(pen)
248 |
249 | painter.drawRect(0, 0, self.width() - 1, self.height() - 1)
250 |
251 | def get_id_str(self):
252 | return f'ID: {self.id} |'
253 |
254 | def get_status_str(self):
255 | status_str = 'Status: '
256 | if self.status == STATUS_QUALITY_VALID:
257 | status_str += "Vaild"
258 | elif self.status == STATUS_FAILSAFE:
259 | status_str += "Failsafe"
260 | else:
261 | status_str += "Unknown"
262 | status_str += ' |'
263 | return status_str
264 |
265 | def get_channel_qty(self):
266 | return len(self.rcin)
267 |
268 | def get_sliders(self):
269 | return self.sliders
270 |
271 | def update_display_channels(self, value):
272 | for i, slider in enumerate(self.get_sliders()):
273 | slider.setVisible(i < value)
274 |
275 | def update_info(self, status, quality, rcin):
276 | self.status = status
277 | self.quality = quality
278 | self.rcin = rcin
279 |
280 | self.status_label.setText(self.get_status_str())
281 | self.channel_num_label.setText(f'CH: {self.get_channel_qty()} |')
282 | self.quality_label.setText(f'Quality: {self.quality} ')
283 | self.rc_quality_widget.set_quality(quality)
284 |
285 | for i in range(DRONECAN_MAX_RC_CHANNELS):
286 | if i < len(rcin):
287 | self.sliders[i].setValid(True)
288 | self.sliders[i].update_channel_value(rcin[i])
289 | else:
290 | self.sliders[i].setValid(False)
291 | self.sliders[i].update_channel_value(CHANNEL_CENTER_VALUE)
292 |
293 | class RcPanel(QDialog):
294 | update_values_signal = pyqtSignal(list)
295 |
296 | def __init__(self, parent, node):
297 | super(RcPanel, self).__init__(parent)
298 | self.setWindowTitle('RC Panel')
299 | self.setAttribute(Qt.WA_DeleteOnClose)
300 |
301 | self._node = node
302 |
303 | self.display_channels = DEFAULT_DISPLAY_CHANNELS
304 |
305 | setting_layout = QHBoxLayout()
306 | self.display_channel_spinbox = QSpinBox()
307 | self.display_channel_spinbox.setRange(1, DRONECAN_MAX_RC_CHANNELS)
308 | self.display_channel_spinbox.setValue(self.display_channels)
309 | self.display_channel_spinbox.setFixedWidth(50)
310 | self.display_channel_spinbox.valueChanged.connect(self.handle_display_channels_value_changed)
311 |
312 | setting_layout.addWidget(QLabel('Display Channels:'))
313 | setting_layout.addWidget(self.display_channel_spinbox)
314 | setting_layout.addStretch(1)
315 |
316 | self.idle_content = QLabel('No RC Instance Available.')
317 |
318 | self.rc_layout = QVBoxLayout()
319 | self.rc_layout.addWidget(self.idle_content)
320 |
321 | self.rc_instances = {}
322 |
323 | layout = QVBoxLayout()
324 |
325 | layout.addLayout(setting_layout)
326 | layout.addLayout(self.rc_layout)
327 |
328 | self.setLayout(layout)
329 |
330 | self.update_values_signal.connect(self.update_channel_values)
331 | self._node.add_handler(dronecan.dronecan.sensors.rc.RCInput, self.handle_RCInput)
332 |
333 | def handle_RCInput(self, msg):
334 | rc_status = []
335 | rc_status.append(msg.message.id)
336 | rc_status.append(msg.message.status)
337 | rc_status.append(msg.message.quality)
338 | rc_status.append(msg.message.rcin)
339 | if not sip.isdeleted(self):
340 | self.update_values_signal.emit(rc_status)
341 |
342 | def update_channel_values(self, rc_status):
343 | rc_id = rc_status[0]
344 | rc_instance = self.rc_instances.get(rc_id, None)
345 | if rc_instance is None:
346 | rc_instance = RcInfoWidget(rc_id)
347 | rc_instance.setMinimumHeight(200)
348 | rc_instance.update_display_channels(self.display_channels)
349 | self.rc_instances[rc_id] = rc_instance
350 | self.rc_layout.addWidget(rc_instance)
351 |
352 | rc_instance.update_info(rc_status[1], rc_status[2], rc_status[3])
353 | self.idle_content.hide()
354 |
355 | def handle_display_channels_value_changed(self, value):
356 | self.display_channels = value
357 | for rc_instance in self.rc_instances.values():
358 | rc_instance.update_display_channels(value)
359 | self.adjustSize()
360 |
361 | def __del__(self):
362 | global _singleton
363 | _singleton = None
364 |
365 | def closeEvent(self, event):
366 | super(RcPanel, self).closeEvent(event)
367 | self.__del__()
368 |
369 | def spawn(parent, node):
370 | global _singleton
371 | if _singleton is None:
372 | try:
373 | _singleton = RcPanel(parent, node)
374 | except Exception as ex:
375 | print(ex)
376 |
377 | _singleton.show()
378 | _singleton.raise_()
379 | _singleton.activateWindow()
380 |
381 | return _singleton
382 |
383 | get_icon = partial(get_icon, 'fa6s.asterisk')
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/rtcm3.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | '''Decode RTCM v3 messages'''
3 |
4 | RTCMv3_PREAMBLE = 0xD3
5 | POLYCRC24 = 0x1864CFB
6 |
7 | import struct
8 |
9 | class RTCM3:
10 | def __init__(self, debug=False):
11 | self.crc_table = None
12 | self.debug = debug
13 | self.discarded = []
14 | self.reset()
15 |
16 | def get_packet(self):
17 | '''return bytearray of last parsed packet'''
18 | return self.parsed_pkt
19 |
20 | def get_packet_ID(self):
21 | '''get get of packet, or None'''
22 | if self.parsed_pkt is None or len(self.parsed_pkt) < 8:
23 | return None
24 | id, = struct.unpack('>H', self.parsed_pkt[3:5])
25 | id >>= 4
26 | return id
27 |
28 | def reset(self):
29 | '''reset state'''
30 | self.pkt = bytearray()
31 | self.pkt_len = 0
32 | self.parsed_pkt = None
33 |
34 | def parse(self):
35 | '''parse packet'''
36 | parity = self.pkt[-3:]
37 | crc1 = parity[0] << 16 | parity[1] << 8 | parity[2]
38 | crc2 = self.crc24(self.pkt[:-3])
39 | if crc1 != crc2:
40 | if self.debug:
41 | # print all the bytes in the packet
42 | print("{",", ".join(["%02x" % b for b in self.pkt]), "}")
43 | print("crc fail len=%u" % len(self.pkt))
44 | # look for preamble
45 | idx = self.pkt[1:].find(bytearray([RTCMv3_PREAMBLE]))
46 | if idx >= 0:
47 | self.pkt = self.pkt[1+idx:]
48 | if len(self.pkt) >= 3:
49 | self.pkt_len, = struct.unpack('>H', self.pkt[1:3])
50 | self.pkt_len &= 0x3ff
51 | else:
52 | self.pkt_len = 0
53 | else:
54 | self.reset()
55 | return False
56 |
57 | # got a good packet
58 | self.parsed_pkt = self.pkt
59 | self.pkt = bytearray()
60 | self.pkt_len = 0
61 | return True
62 |
63 | def read(self, byte):
64 | '''read in one byte, return true if a full packet is available'''
65 |
66 | #import random
67 | #if random.uniform(0,1000) < 1:
68 | # return False
69 |
70 | byte = ord(byte)
71 | if len(self.pkt) == 0 and byte != RTCMv3_PREAMBLE:
72 | # discard
73 | self.discarded.append(byte)
74 | return False
75 | if len(self.discarded) > 0:
76 | print("{",", ".join(["%02x" % b for b in self.discarded]), "}")
77 | self.discarded = []
78 | self.pkt.append(byte)
79 | if self.pkt_len == 0 and len(self.pkt) >= 3:
80 | self.pkt_len, = struct.unpack('>H', self.pkt[1:3])
81 | self.pkt_len &= 0x3ff
82 | if self.pkt_len == 0:
83 | self.reset()
84 | return False
85 |
86 | if self.pkt_len > 0 and len(self.pkt) >= 3 + self.pkt_len + 3:
87 | remainder = self.pkt[6+self.pkt_len:]
88 | self.pkt = self.pkt[:6+self.pkt_len]
89 | # got header, packet body and parity
90 | ret = self.parse()
91 | self.pkt.extend(remainder)
92 | return ret
93 |
94 | # need more bytes
95 | return False
96 |
97 | def crc24(self, bytes):
98 | '''calculate 24 bit crc'''
99 | if self.crc_table is None:
100 | # initialise table
101 | self.crc_table = [0] * 256
102 | for i in range(256):
103 | self.crc_table[i] = i<<16
104 | for j in range(8):
105 | self.crc_table[i] <<= 1
106 | if (self.crc_table[i] & 0x1000000):
107 | self.crc_table[i] ^= POLYCRC24
108 | crc = 0
109 | for b in bytes:
110 | crc = ((crc<<8)&0xFFFFFF) ^ self.crc_table[(crc>>16) ^ b]
111 | return crc
112 |
113 | if __name__ == '__main__':
114 | from argparse import ArgumentParser
115 | import time
116 | parser = ArgumentParser(description='RTCM3 parser')
117 |
118 | parser.add_argument("filename", type=str, help="input file")
119 | parser.add_argument("--debug", action='store_true', help="show errors")
120 | parser.add_argument("--follow", action='store_true', help="continue reading on EOF")
121 | args = parser.parse_args()
122 |
123 | rtcm3 = RTCM3(args.debug)
124 | f = open(args.filename, 'rb')
125 | while True:
126 | b = f.read(1)
127 | if len(b) == 0:
128 | if args.follow:
129 | time.sleep(0.1)
130 | continue
131 | break
132 | if rtcm3.read(b):
133 | print("packet len %u ID %u" % (len(rtcm3.get_packet()), rtcm3.get_packet_ID()))
134 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/panels/stats_panel.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2023 DroneCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Siddharth Purohit
7 | #
8 |
9 | import dronecan
10 | from functools import partial
11 | from PyQt5.QtWidgets import QGridLayout, QWidget, QLabel, QDialog, \
12 | QVBoxLayout, QGroupBox, QLineEdit, QPushButton
13 | from PyQt5.QtCore import Qt, QTimer
14 | from ..widgets import get_icon
15 | from ..widgets import table_display
16 | from . import rtcm3
17 | import time
18 | import socket
19 | import errno
20 |
21 | __all__ = 'PANEL_NAME', 'spawn', 'get_icon'
22 |
23 | PANEL_NAME = 'Stats Panel'
24 |
25 | _singleton = None
26 |
27 | class StatsPanel(QDialog):
28 | def __init__(self, parent, node):
29 | super(StatsPanel, self).__init__(parent)
30 | self.setWindowTitle('Stats Panel')
31 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
32 |
33 | layout = QVBoxLayout()
34 |
35 | self.dronecan_stats_table = table_display.TableDisplay(['Node ID', 'Tx Frames', 'Tx Errors', 'Rx Frames', 'Rx Error OOM', 'Rx Error Internal', 'Rx Error Missed Start', 'Rx Error Wrong Toggle', 'Rx Error Short Frame', 'Rx Error Bad CRC', 'Rx Ign Wrong Address', 'Rx Ign Not Wanted', 'Rx Ign Unexpected TID',], expire_time=5.0)
36 | self.setLayout(layout)
37 |
38 | self.dronecan_stats_group = QGroupBox('DroneCAN Stats', self)
39 | self.dronecan_stats_layout = QGridLayout()
40 | self.dronecan_stats_layout.addWidget(self.dronecan_stats_table)
41 | self.dronecan_stats_group.setLayout(self.dronecan_stats_layout)
42 | self.dronecan_stats_group.setToolTip('''
43 | DroneCAN Stats shows the statistics of the DroneCAN network.
44 | ''')
45 | self.can_stats_table = table_display.TableDisplay(['Node ID', 'Interface', 'Tx Requests', 'Tx Rejected', 'Tx Overflow', 'Tx Success', 'Tx Timedout', 'Tx Abort', 'Rx Received', 'Rx Overflow', 'Rx Errors', 'Busoff Errors'], expire_time=5.0)
46 |
47 | self.can_stats_group = QGroupBox('CAN Stats', self)
48 | self.can_stats_layout = QGridLayout()
49 | self.can_stats_layout.addWidget(self.can_stats_table)
50 | self.can_stats_group.setLayout(self.can_stats_layout)
51 | self.can_stats_group.setToolTip('''
52 | CAN Stats shows the statistics of the CAN interface.
53 | ''')
54 |
55 |
56 | layout.addWidget(self.dronecan_stats_group)
57 | layout.addWidget(self.can_stats_group)
58 |
59 | self.clear_stats_button = QPushButton('Clear Stats', self)
60 | self.clear_stats_button.clicked.connect(self.clear_stats)
61 | layout.addWidget(self.clear_stats_button)
62 |
63 | self.setLayout(layout)
64 | self.resize(800, 800)
65 | self.node = node
66 | self.handlers = [node.add_handler(dronecan.dronecan.protocol.Stats, self.on_dronecan_stats),
67 | node.add_handler(dronecan.dronecan.protocol.CanStats, self.on_can_stats)]
68 |
69 | self.dronecan_offsets = {}
70 | self.can_offsets = {}
71 |
72 | def on_dronecan_stats(self, msg):
73 | '''display dronecan stats'''
74 | nodeid = msg.transfer.source_node_id
75 | if nodeid not in self.dronecan_offsets:
76 | self.dronecan_offsets[nodeid] = [0] * 12
77 | offsets = self.dronecan_offsets[nodeid]
78 | self.dronecan_stats_table.update(nodeid, [
79 | nodeid,
80 | msg.message.tx_frames - offsets[0],
81 | msg.message.tx_errors - offsets[1],
82 | msg.message.rx_frames - offsets[2],
83 | msg.message.rx_error_oom - offsets[3],
84 | msg.message.rx_error_internal - offsets[4],
85 | msg.message.rx_error_missed_start - offsets[5],
86 | msg.message.rx_error_wrong_toggle - offsets[6],
87 | msg.message.rx_error_short_frame - offsets[7],
88 | msg.message.rx_error_bad_crc - offsets[8],
89 | msg.message.rx_ignored_wrong_address - offsets[9],
90 | msg.message.rx_ignored_not_wanted - offsets[10],
91 | msg.message.rx_ignored_unexpected_tid - offsets[11]
92 | ])
93 |
94 | def on_can_stats(self, msg):
95 | '''display can stats'''
96 | nodeid = msg.transfer.source_node_id
97 | interface = msg.message.interface
98 | key = (nodeid, interface)
99 | if key not in self.can_offsets:
100 | self.can_offsets[key] = [0] * 11
101 | offsets = self.can_offsets[key]
102 | self.can_stats_table.update(key, [
103 | nodeid,
104 | interface,
105 | msg.message.tx_requests - offsets[0],
106 | msg.message.tx_rejected - offsets[1],
107 | msg.message.tx_overflow - offsets[2],
108 | msg.message.tx_success - offsets[3],
109 | msg.message.tx_timedout - offsets[4],
110 | msg.message.tx_abort - offsets[5],
111 | msg.message.rx_received - offsets[6],
112 | msg.message.rx_overflow - offsets[7],
113 | msg.message.rx_errors - offsets[8],
114 | msg.message.busoff_errors - offsets[9]
115 | ])
116 |
117 | def clear_stats(self):
118 | '''clear all stats and set offsets'''
119 | for nodeid in self.dronecan_stats_table.data.keys():
120 | current_values = self.dronecan_stats_table.data[nodeid][1:]
121 | self.dronecan_offsets[nodeid] = [offset + current for offset, current in zip(self.dronecan_offsets[nodeid], current_values)]
122 |
123 | for key in self.can_stats_table.data.keys():
124 | current_values = self.can_stats_table.data[key][2:]
125 | self.can_offsets[key] = [offset + current for offset, current in zip(self.can_offsets[key], current_values)]
126 |
127 | def __del__(self):
128 | for h in self.handlers:
129 | h.remove()
130 | global _singleton
131 | _singleton = None
132 |
133 | def closeEvent(self, event):
134 | super(StatsPanel, self).closeEvent(event)
135 | self.__del__()
136 |
137 | def spawn(parent, node):
138 | global _singleton
139 | if _singleton is None:
140 | try:
141 | _singleton = StatsPanel(parent, node)
142 | except Exception as ex:
143 | print(ex)
144 |
145 | _singleton.show()
146 | _singleton.raise_()
147 | _singleton.activateWindow()
148 |
149 | return _singleton
150 |
151 | get_icon = partial(get_icon, 'fa6s.asterisk')
152 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/setup_window.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import sys
10 | import glob
11 | import time
12 | import threading
13 | import copy
14 | from .widgets import show_error, get_monospace_font, directory_selection
15 | from PyQt5.QtWidgets import QComboBox, QCompleter, QDialog, QDirModel, QFileDialog, QGroupBox, QHBoxLayout, QLabel, \
16 | QLineEdit, QPushButton, QSpinBox, QVBoxLayout, QGridLayout, QCheckBox, QWidget
17 | from qtwidgets import PasswordEdit
18 | from PyQt5.QtCore import Qt, QTimer
19 | from PyQt5.QtGui import QIntValidator
20 | from logging import getLogger
21 | from collections import OrderedDict
22 | from itertools import count
23 | import re
24 |
25 |
26 | STANDARD_BAUD_RATES = 9600, 115200, 460800, 921600, 1000000, 3000000
27 | DEFAULT_BAUD_RATE = 115200
28 | assert DEFAULT_BAUD_RATE in STANDARD_BAUD_RATES
29 |
30 |
31 | RUNNING_ON_LINUX = 'linux' in sys.platform.lower()
32 |
33 | MACOS_SERIAL_PORTS_FILTER = ['/dev/tty.debug-console', '/dev/tty.wlan-debug', '/dev/tty.Bluetooth-Incoming-Port']
34 | logger = getLogger(__name__)
35 |
36 |
37 | def _linux_parse_proc_net_dev(out_ifaces):
38 | with open('/proc/net/dev') as f:
39 | for line in f:
40 | if ':' in line:
41 | name = line.split(':')[0].strip()
42 | out_ifaces.insert(0 if 'can' in name else len(out_ifaces), name)
43 | return out_ifaces
44 |
45 |
46 | def _linux_parse_ip_link_show(out_ifaces):
47 | import re
48 | import subprocess
49 | import tempfile
50 |
51 | with tempfile.TemporaryFile() as f:
52 | proc = subprocess.Popen('ip link show', shell=True, stdout=f)
53 | if 0 != proc.wait(10):
54 | raise RuntimeError('Process failed')
55 | f.seek(0)
56 | out = f.read().decode()
57 |
58 | return re.findall(r'\d+?: ([a-z0-9]+?): <[^>]*UP[^>]*>.*\n *link/can', out) + out_ifaces
59 |
60 | def _mavcan_interfaces():
61 | '''extra CAN over mavlink interfaces'''
62 | try:
63 | from pymavlink import mavutil
64 | except ImportError:
65 | return []
66 | return ['mavcan::14550']
67 |
68 | def list_ifaces():
69 | """Returns dictionary, where key is description, value is the OS assigned name of the port"""
70 | logger.debug('Updating iface list...')
71 | if RUNNING_ON_LINUX:
72 | # Linux system
73 | ifaces = glob.glob('/dev/serial/by-id/*')
74 | try:
75 | ifaces = list(sorted(ifaces,
76 | key=lambda s: not ('zubax' in s.lower() and 'babel' in s.lower())))
77 | except Exception:
78 | logger.warning('Sorting failed', exc_info=True)
79 |
80 | # noinspection PyBroadException
81 | try:
82 | ifaces = _linux_parse_ip_link_show(ifaces) # Primary
83 | except Exception as ex:
84 | logger.warning('Could not parse "ip link show": %s', ex, exc_info=True)
85 | ifaces = _linux_parse_proc_net_dev(ifaces) # Fallback
86 |
87 | ifaces += _mavcan_interfaces()
88 | ifaces += ["mcast:0", "mcast:1"]
89 |
90 | out = OrderedDict()
91 | for x in ifaces:
92 | out[x] = x
93 |
94 | return out
95 | else:
96 | # Windows, Mac, whatever
97 | from PyQt5 import QtSerialPort
98 |
99 | out = OrderedDict()
100 | for port in QtSerialPort.QSerialPortInfo.availablePorts():
101 | if sys.platform == 'darwin':
102 | if 'tty' in port.systemLocation():
103 | if port.systemLocation() not in MACOS_SERIAL_PORTS_FILTER:
104 | out[port.systemLocation()] = port.systemLocation()
105 | else:
106 | sys_name = port.systemLocation()
107 | sys_alpha = re.sub(r'[^a-zA-Z0-9]', '', sys_name)
108 | description = port.description()
109 | # show the COM port in parentheses to make it clearer which port it is
110 | out["%s (%s)" % (description, sys_alpha)] = sys_name
111 |
112 | mifaces = _mavcan_interfaces()
113 | mifaces += ["mcast:0", "mcast:1"]
114 | for x in mifaces:
115 | out[x] = x
116 |
117 | try:
118 | if sys.platform != 'darwin':
119 | from can import detect_available_configs
120 | try:
121 | import pythoncom
122 | pythoncom.CoInitialize()
123 | except Exception:
124 | pass
125 | for interface in detect_available_configs():
126 | if interface['interface'] == "pcan":
127 | out[interface['channel']] = interface['channel']
128 | except Exception as ex:
129 | logger.warning('Could not load can interfaces: %s', ex, exc_info=True)
130 |
131 | return out
132 |
133 |
134 | class BackgroundIfaceListUpdater:
135 | UPDATE_INTERVAL = 0.5
136 |
137 | def __init__(self):
138 | self._ifaces = list_ifaces()
139 | self._thread = threading.Thread(target=self._run, name='iface_lister', daemon=True)
140 | self._keep_going = True
141 | self._lock = threading.Lock()
142 |
143 | def __enter__(self):
144 | logger.debug('Starting iface list updater')
145 | self._thread.start()
146 | return self
147 |
148 | def __exit__(self, *_):
149 | logger.debug('Stopping iface list updater...')
150 | self._keep_going = False
151 | self._thread.join()
152 | logger.debug('Stopped iface list updater')
153 |
154 | def _run(self):
155 | while self._keep_going:
156 | time.sleep(self.UPDATE_INTERVAL)
157 | new_list = list_ifaces()
158 | with self._lock:
159 | self._ifaces = new_list
160 |
161 | def get_list(self):
162 | with self._lock:
163 | return copy.copy(self._ifaces)
164 |
165 |
166 | def run_setup_window(icon, dsdl_path=None, config_baudrate=DEFAULT_BAUD_RATE, config_bitrate=1000000, config_can_bus=1, enable_filtering=False, mavlink_target_system=0, mavlink_signing_key=''):
167 | win = QDialog()
168 | win.setWindowTitle('Application Setup')
169 | win.setWindowIcon(icon)
170 | win.setWindowFlags(Qt.CustomizeWindowHint | Qt.WindowTitleHint | Qt.WindowCloseButtonHint)
171 | win.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
172 |
173 | combo = QComboBox(win)
174 | combo.setEditable(True)
175 | combo.setInsertPolicy(QComboBox.NoInsert)
176 | combo.setSizeAdjustPolicy(QComboBox.AdjustToContents)
177 | combo.setFont(get_monospace_font())
178 |
179 | combo_completer = QCompleter()
180 | combo_completer.setCaseSensitivity(Qt.CaseSensitive)
181 | combo_completer.setModel(combo.model())
182 | combo.setCompleter(combo_completer)
183 |
184 | bitrate = QSpinBox(win)
185 | bitrate.setMaximum(1000000)
186 | bitrate.setMinimum(10000)
187 | bitrate.setValue(config_bitrate)
188 |
189 | bus_number = QSpinBox(win)
190 | bus_number.setMaximum(4)
191 | bus_number.setMinimum(1)
192 | bus_number.setValue(config_can_bus)
193 |
194 | baudrate = QComboBox(win)
195 | baudrate.setEditable(True)
196 | baudrate.setInsertPolicy(QComboBox.NoInsert)
197 | baudrate.setSizeAdjustPolicy(QComboBox.AdjustToContents)
198 | baudrate.setFont(get_monospace_font())
199 |
200 | baudrate_completer = QCompleter(win)
201 | baudrate_completer.setModel(baudrate.model())
202 | baudrate.setCompleter(baudrate_completer)
203 |
204 | baudrate.setValidator(QIntValidator(min(STANDARD_BAUD_RATES), max(STANDARD_BAUD_RATES)))
205 | baudrate.insertItems(0, map(str, STANDARD_BAUD_RATES))
206 | baudrate.setCurrentText(str(config_baudrate))
207 |
208 | filtered = QCheckBox('Enable Filtering')
209 | filtered.setChecked(enable_filtering)
210 |
211 | target_system = QSpinBox(win)
212 | target_system.setMaximum(255)
213 | target_system.setMinimum(0)
214 | target_system.setValue(mavlink_target_system)
215 |
216 | signing_key = PasswordEdit(win)
217 | signing_key.setText(mavlink_signing_key)
218 |
219 | dir_selection = directory_selection.DirectorySelectionWidget(win, 'Location of custom DSDL definitions [optional]', path=dsdl_path, directory_only=True)
220 |
221 | ok = QPushButton('OK', win)
222 |
223 | ifaces = None
224 |
225 | def update_iface_list():
226 | nonlocal ifaces
227 | ifaces = iface_lister.get_list()
228 | known_keys = set()
229 | remove_indices = []
230 | was_empty = combo.count() == 0
231 | # Marking known and scheduling for removal
232 | for idx in count():
233 | tx = combo.itemText(idx)
234 | if not tx:
235 | break
236 | known_keys.add(tx)
237 | if tx not in list(ifaces.keys()):
238 | logger.debug('Removing iface %r', tx)
239 | remove_indices.append(idx)
240 | # Removing - starting from the last item in order to retain indexes
241 | for idx in remove_indices[::-1]:
242 | combo.removeItem(idx)
243 | # Adding new items - starting from the last item in order to retain the final order
244 | for key in list(ifaces.keys())[::-1]:
245 | if key and key not in known_keys:
246 | logger.debug('Adding iface %r', key)
247 | combo.insertItem(0, key)
248 | # Updating selection
249 | if was_empty:
250 | combo.setCurrentIndex(0)
251 |
252 | result = None
253 | kwargs = {}
254 |
255 | def on_ok():
256 | nonlocal result, kwargs
257 | try:
258 | baud_rate_value = int(baudrate.currentText())
259 | except ValueError:
260 | show_error('Invalid parameters', 'Could not parse baud rate', 'Please specify correct baud rate',
261 | parent=win)
262 | return
263 | if not (min(STANDARD_BAUD_RATES) <= baud_rate_value <= max(STANDARD_BAUD_RATES)):
264 | show_error('Invalid parameters', 'Baud rate is out of range',
265 | 'Baud rate value should be within [%s, %s]' %
266 | (min(STANDARD_BAUD_RATES), max(STANDARD_BAUD_RATES)),
267 | parent=win)
268 | return
269 | kwargs['baudrate'] = baud_rate_value
270 | kwargs['bitrate'] = int(bitrate.value())
271 | kwargs['bus_number'] = int(bus_number.value())
272 | kwargs['filtered'] = filtered.checkState()
273 | kwargs['mavlink_target_system'] = int(target_system.value())
274 | kwargs['mavlink_signing_key'] = signing_key.text()
275 | result_key = str(combo.currentText()).strip()
276 | if not result_key:
277 | show_error('Invalid parameters', 'Interface name cannot be empty', 'Please select a valid interface',
278 | parent=win)
279 | return
280 | try:
281 | result = ifaces[result_key]
282 | except KeyError:
283 | result = result_key
284 | win.close()
285 |
286 | ok.clicked.connect(on_ok)
287 |
288 | can_group = QGroupBox('CAN interface setup', win)
289 | can_layout = QVBoxLayout()
290 | can_layout.addWidget(QLabel('Select CAN interface'))
291 | can_layout.addWidget(combo)
292 |
293 | adapter_group = QGroupBox('Adapter settings', win)
294 | adapter_layout = QGridLayout()
295 | adapter_layout.addWidget(QLabel('Bus Number:'), 0, 0)
296 | adapter_layout.addWidget(bus_number, 0, 1)
297 | adapter_layout.addWidget(QLabel('CAN bus bit rate:'), 1, 0)
298 | adapter_layout.addWidget(bitrate, 1, 1)
299 | adapter_layout.addWidget(QLabel('Adapter baud rate (not applicable to USB):'), 2, 0)
300 | adapter_layout.addWidget(baudrate, 2, 1)
301 | adapter_layout.addWidget(QLabel('Filter for low bandwidth:'), 3, 0)
302 | adapter_layout.addWidget(filtered, 3, 1)
303 | adapter_layout.addWidget(QLabel('MAVLink target system (0 for auto):'), 4, 0)
304 | adapter_layout.addWidget(target_system, 4, 1)
305 | adapter_layout.addWidget(QLabel('MAVLink signing key:'), 5, 0)
306 | adapter_layout.addWidget(signing_key, 5, 1)
307 |
308 | adapter_group.setLayout(adapter_layout)
309 |
310 | can_layout.addWidget(adapter_group)
311 | can_group.setLayout(can_layout)
312 |
313 | layout = QVBoxLayout()
314 | layout.addWidget(can_group)
315 | layout.addWidget(dir_selection)
316 | layout.addWidget(ok)
317 | layout.setSizeConstraint(layout.SetFixedSize)
318 | win.setLayout(layout)
319 |
320 | QWidget.setTabOrder(combo, bus_number)
321 | QWidget.setTabOrder(bus_number, bitrate)
322 | QWidget.setTabOrder(bitrate, baudrate)
323 | QWidget.setTabOrder(baudrate, filtered)
324 | QWidget.setTabOrder(filtered, target_system)
325 | QWidget.setTabOrder(target_system, signing_key)
326 | QWidget.setTabOrder(signing_key, dir_selection)
327 | QWidget.setTabOrder(dir_selection, ok)
328 | QWidget.setTabOrder(ok, combo)
329 |
330 | with BackgroundIfaceListUpdater() as iface_lister:
331 | update_iface_list()
332 | timer = QTimer(win)
333 | timer.setSingleShot(False)
334 | timer.timeout.connect(update_iface_list)
335 | timer.start(int(BackgroundIfaceListUpdater.UPDATE_INTERVAL / 2 * 1000))
336 | win.exec()
337 |
338 | return result, kwargs, dir_selection.get_selection()
339 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/version.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 DroneCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | # David Buzz
8 | # Andrew Tridgell
9 | #
10 | #
11 | __version__ = 1, 2, 28
12 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/about_window.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import dronecan
10 | from ..version import __version__
11 | from . import get_icon, get_app_icon
12 | from PyQt5.QtWidgets import QDialog, QTableWidget, QVBoxLayout, QHBoxLayout, QPushButton, QLabel, \
13 | QTableWidgetItem, QHeaderView
14 | from PyQt5.QtGui import QIcon
15 | from PyQt5.QtCore import Qt, PYQT_VERSION_STR, QSize
16 |
17 |
18 | ABOUT_TEXT = ('''
19 | DroneCAN GUI Tool v{0}
20 | Cross-platform application for DroneCAN bus management and diagnostics.
21 |
22 | This application is distributed under the terms of the MIT software license. The source repository and the bug \
23 | tracker are located at https://github.com/DroneCAN/gui_tool.
24 | '''.format('.'.join(map(str, __version__)))).strip().replace('\n', '\n
')
25 |
26 |
27 | def _list_3rd_party():
28 | import pyqtgraph
29 | import qtawesome
30 |
31 | try:
32 | from qtconsole import __version__ as qtconsole_version
33 | from IPython import __version__ as ipython_version
34 | except ImportError:
35 | qtconsole_version = 'N/A'
36 | ipython_version = 'N/A'
37 | try:
38 | from pymavlink import __version__ as pymavlink_version
39 | except ImportError:
40 | pymavlink_version = 'N/A'
41 |
42 | return [
43 | ('PyDroneCAN', dronecan.__version__, 'MIT', 'http://dronecan.org/Implementations/Pydronecan'),
44 | ('PyQt5', PYQT_VERSION_STR, 'GPLv3', 'https://www.riverbankcomputing.com/software/pyqt/intro'),
45 | ('PyQtGraph', pyqtgraph.__version__, 'MIT', 'http://www.pyqtgraph.org/'),
46 | ('QtAwesome', qtawesome.__version__, 'MIT', 'https://github.com/spyder-ide/qtawesome'),
47 | ('QtConsole', qtconsole_version, 'BSD', 'http://jupyter.org'),
48 | ('IPython', ipython_version, 'BSD', 'https://ipython.org'),
49 | ('pymavlink', pymavlink_version, 'LGPLv3+', 'http://github.com/ardupilot/pymavlink'),
50 | ]
51 |
52 |
53 | class AboutWindow(QDialog):
54 | def __init__(self, parent):
55 | super(AboutWindow, self).__init__(parent)
56 | self.setAttribute(Qt.WA_DeleteOnClose)
57 | self.setWindowTitle('About DroneCAN GUI Tool')
58 |
59 | #
60 | # Icon
61 | #
62 | icon_size = 128
63 | canvas_size = 150
64 | pixmap = get_app_icon().pixmap(QSize(icon_size, icon_size), QIcon.Normal, QIcon.On)
65 | self._icon = QLabel(self)
66 | self._icon.setPixmap(pixmap)
67 | self._icon.setAlignment(Qt.AlignCenter)
68 | self._icon.setMinimumSize(QSize(canvas_size, canvas_size))
69 |
70 | #
71 | # Description text
72 | #
73 | self._description = QLabel(self)
74 | self._description.setWordWrap(True)
75 | self._description.setTextFormat(Qt.RichText)
76 | self._description.setTextInteractionFlags(Qt.TextBrowserInteraction)
77 | self._description.setOpenExternalLinks(True)
78 | self._description.setText(ABOUT_TEXT)
79 |
80 | #
81 | # List of third-party components
82 | #
83 | third_party = _list_3rd_party()
84 |
85 | self._components = QTableWidget(self)
86 | self._components.setShowGrid(False)
87 | self._components.verticalHeader().setVisible(False)
88 | self._components.setRowCount(len(third_party))
89 | self._components.setColumnCount(len(third_party[0]))
90 | self._components.setWordWrap(False)
91 | self._components.setHorizontalHeaderLabels(['Component', 'Version', 'License', 'Home page'])
92 |
93 | for row, component in enumerate(third_party):
94 | for col, field in enumerate(component):
95 | if field is not None:
96 | w = QTableWidgetItem(str(field))
97 | w.setFlags(Qt.ItemIsEnabled | Qt.ItemIsSelectable)
98 | self._components.setItem(row, col, w)
99 |
100 | self._components.resizeRowsToContents()
101 | self._components.resizeColumnsToContents()
102 | self._components.horizontalHeader().setSectionResizeMode(0, QHeaderView.Stretch)
103 |
104 | #
105 | # Window layout
106 | #
107 | self._exit_button = QPushButton(get_icon('fa6s.check'), 'OK', self)
108 | self._exit_button.clicked.connect(self.close)
109 |
110 | layout = QVBoxLayout(self)
111 | top_layout = QHBoxLayout(self)
112 | top_layout.addWidget(self._icon)
113 | top_layout.addWidget(self._description, 1)
114 | layout.addLayout(top_layout)
115 | layout.addWidget(self._components, 1)
116 | layout.addWidget(self._exit_button)
117 | self.setLayout(layout)
118 |
119 | self.setMinimumSize(QSize(600, 300))
120 | self.resize(QSize(700, 400))
121 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/bus_monitor/__init__.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import os
10 | import sys
11 | import queue
12 | import logging
13 | import multiprocessing
14 | from PyQt5.QtWidgets import QApplication
15 | from PyQt5.QtCore import QTimer
16 | from .window import BusMonitorWindow
17 |
18 | logger = logging.getLogger(__name__)
19 |
20 | try:
21 | # noinspection PyUnresolvedReferences
22 | sys.getwindowsversion()
23 | RUNNING_ON_WINDOWS = True
24 | except AttributeError:
25 | RUNNING_ON_WINDOWS = False
26 | PARENT_PID = os.getppid()
27 |
28 |
29 | class IPCChannel:
30 | """
31 | This class is built as an abstraction over the underlying IPC communication channel.
32 | """
33 | def __init__(self):
34 | # Queue is slower than pipe, but it allows to implement non-blocking sending easier,
35 | # and the buffer can be arbitrarily large.
36 | self._q = multiprocessing.Queue()
37 |
38 | def send_nonblocking(self, obj):
39 | try:
40 | self._q.put_nowait(obj)
41 | except queue.Full:
42 | pass
43 |
44 | def receive_nonblocking(self):
45 | """Returns: (True, object) if successful, (False, None) if no data to read """
46 | try:
47 | return True, self._q.get_nowait()
48 | except queue.Empty:
49 | return False, None
50 |
51 |
52 | IPC_COMMAND_STOP = 'stop'
53 |
54 |
55 | def _process_entry_point(channel, iface_name):
56 | logger.info('Bus monitor process started with PID %r', os.getpid())
57 | app = QApplication(sys.argv) # Inheriting args from the parent process
58 |
59 | def exit_if_should():
60 | if RUNNING_ON_WINDOWS:
61 | return False
62 | else:
63 | return os.getppid() != PARENT_PID # Parent is dead
64 |
65 | exit_check_timer = QTimer()
66 | exit_check_timer.setSingleShot(False)
67 | exit_check_timer.timeout.connect(exit_if_should)
68 | exit_check_timer.start(2000)
69 |
70 | def get_frame():
71 | received, obj = channel.receive_nonblocking()
72 | if received:
73 | if obj == IPC_COMMAND_STOP:
74 | logger.info('Bus monitor process has received a stop request, goodbye')
75 | app.exit(0)
76 | else:
77 | return obj
78 |
79 | win = BusMonitorWindow(get_frame, iface_name)
80 | win.show()
81 |
82 | logger.info('Bus monitor process %r initialized successfully, now starting the event loop', os.getpid())
83 | sys.exit(app.exec_())
84 |
85 |
86 | # TODO: Duplicates PlotterManager; refactor into an abstract process factory
87 | class BusMonitorManager:
88 | def __init__(self, node, can_iface_name):
89 | self._node = node
90 | self._can_iface_name = can_iface_name
91 | self._inferiors = [] # process object, channel
92 | self._hook_handle = None
93 |
94 | def _frame_hook(self, direction, frame):
95 | for proc, channel in self._inferiors[:]:
96 | if proc.is_alive():
97 | try:
98 | channel.send_nonblocking((direction, frame))
99 | except Exception:
100 | logger.error('Failed to send data to process %r', proc, exc_info=True)
101 | else:
102 | logger.info('Bus monitor process %r appears to be dead, removing', proc)
103 | self._inferiors.remove((proc, channel))
104 |
105 | def spawn_monitor(self):
106 | channel = IPCChannel()
107 |
108 | if self._hook_handle is None:
109 | self._hook_handle = self._node.can_driver.add_io_hook(self._frame_hook)
110 |
111 | proc = multiprocessing.Process(target=_process_entry_point, name='bus_monitor',
112 | args=(channel, self._can_iface_name))
113 | proc.daemon = True
114 | proc.start()
115 |
116 | self._inferiors.append((proc, channel))
117 |
118 | logger.info('Spawned new bus monitor process %r', proc)
119 |
120 | def close(self):
121 | try:
122 | self._hook_handle.remove()
123 | except Exception:
124 | pass
125 |
126 | for _, channel in self._inferiors:
127 | try:
128 | channel.send_nonblocking(IPC_COMMAND_STOP)
129 | except Exception:
130 | pass
131 |
132 | for proc, _ in self._inferiors:
133 | try:
134 | proc.join(1)
135 | except Exception:
136 | pass
137 |
138 | for proc, _ in self._inferiors:
139 | try:
140 | proc.terminate()
141 | except Exception:
142 | pass
143 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/bus_monitor/transfer_decoder.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import dronecan
10 | from dronecan.transport import Transfer, Frame
11 |
12 | # How many rows will be traversed while looking for beginning/end of a multi frame transfer
13 | TABLE_TRAVERSING_RANGE = 2000
14 |
15 |
16 | class DecodingFailedException(Exception):
17 | pass
18 |
19 |
20 | def _get_transfer_id(frame):
21 | if len(frame.data):
22 | return frame.data[-1] & 0b00011111
23 |
24 |
25 | def _is_start_of_transfer(frame):
26 | if len(frame.data):
27 | return frame.data[-1] & 0b10000000
28 |
29 |
30 | def _is_end_of_transfer(frame):
31 | if len(frame.data):
32 | return frame.data[-1] & 0b01000000
33 |
34 |
35 | def decode_transfer_from_frame(entry_row, row_to_frame):
36 | entry_frame, direction = row_to_frame(entry_row)
37 | can_id = entry_frame.id
38 | transfer_id = _get_transfer_id(entry_frame)
39 | frames = [entry_frame]
40 |
41 | related_rows = []
42 |
43 | # Scanning backward looking for the first frame
44 | row = entry_row - 1
45 | while not _is_start_of_transfer(frames[0]):
46 | if row < 0 or entry_row - row > TABLE_TRAVERSING_RANGE:
47 | raise DecodingFailedException('SOT not found')
48 | f, d = row_to_frame(row)
49 | row -= 1
50 | if f.id == can_id and _get_transfer_id(f) == transfer_id and d == direction:
51 | frames.insert(0, f)
52 | related_rows.insert(0, row)
53 |
54 | # Scanning forward looking for the last frame
55 | row = entry_row + 1
56 | while not _is_end_of_transfer(frames[-1]):
57 | f, d = row_to_frame(row)
58 | if f is None or row - entry_row > TABLE_TRAVERSING_RANGE:
59 | raise DecodingFailedException('EOT not found')
60 | row += 1
61 | if f.id == can_id and _get_transfer_id(f) == transfer_id and d == direction:
62 | frames.append(f)
63 | related_rows.append(row)
64 |
65 | # The transfer is now fully recovered
66 | tr = Transfer()
67 | tr.from_frames([Frame(x.id, x.data, canfd=x.canfd) for x in frames])
68 |
69 | return related_rows, dronecan.to_yaml(tr.payload)
70 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/can_adapter_control_panel/__init__.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | from PyQt5.QtWidgets import QProgressDialog, QMessageBox
10 | from . import slcan_cli
11 |
12 |
13 | def spawn_window(parent, node, iface_name):
14 | driver = node.can_driver
15 |
16 | if not slcan_cli.CLIInterface.is_backend_supported(driver):
17 | mbox = QMessageBox(parent)
18 | mbox.setWindowTitle('Unsupported CAN Backend')
19 | mbox.setText('CAN Adapter Control Panel cannot be used with the current CAN backend.')
20 | mbox.setInformativeText('The current backend is %r.' % type(driver).__name__)
21 | mbox.setIcon(QMessageBox.Information)
22 | mbox.setStandardButtons(QMessageBox.Ok)
23 | mbox.show() # Not exec() because we don't want it to block!
24 | return
25 |
26 | progress_dialog = QProgressDialog(parent)
27 | progress_dialog.setWindowTitle('CAN Adapter Control Panel Initialization')
28 | progress_dialog.setLabelText('Detecting CAN adapter capabilities...')
29 | progress_dialog.setMinimumDuration(800)
30 | progress_dialog.setCancelButton(None)
31 | progress_dialog.setRange(0, 0)
32 | progress_dialog.show()
33 |
34 | def supported_callback(supported):
35 | progress_dialog.close()
36 |
37 | if not supported:
38 | mbox = QMessageBox(parent)
39 | mbox.setWindowTitle('Incompatible CAN Adapter')
40 | mbox.setText('CAN Adapter Control Panel cannot be used with the connected adapter.')
41 | mbox.setInformativeText('Connected SLCAN adapter does not support CLI extensions.')
42 | mbox.setIcon(QMessageBox.Information)
43 | mbox.setStandardButtons(QMessageBox.Ok)
44 | mbox.show() # Not exec() because we don't want it to block!
45 | return
46 |
47 | slcp = slcan_cli.ControlPanelWindow(parent, slcan_iface, iface_name)
48 | slcp.show()
49 |
50 | slcan_iface = slcan_cli.CLIInterface(driver)
51 | slcan_iface.check_is_interface_supported(supported_callback)
52 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/console.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import sys
10 | import logging
11 | from PyQt5.QtWidgets import QDialog, QVBoxLayout, QHBoxLayout, QComboBox, QLabel, QCheckBox
12 | from PyQt5.QtCore import QTimer, Qt
13 |
14 | logger = logging.getLogger(__name__)
15 |
16 | try:
17 | # noinspection PyUnresolvedReferences
18 | from qtconsole.rich_jupyter_widget import RichJupyterWidget
19 | # noinspection PyUnresolvedReferences
20 | from qtconsole.inprocess import QtInProcessKernelManager
21 |
22 | JUPYTER_AVAILABLE = True
23 | except ImportError:
24 | JUPYTER_AVAILABLE = False
25 | logger.info('Jupyter is not available', exc_info=True)
26 |
27 |
28 | if JUPYTER_AVAILABLE:
29 | class JupyterWidget(RichJupyterWidget):
30 | def __init__(self, parent, kernel_manager, banner=None):
31 | super(JupyterWidget, self).__init__(parent)
32 |
33 | self.kernel_manager = kernel_manager
34 |
35 | self.kernel_client = kernel_manager.client()
36 | self.kernel_client.start_channels()
37 |
38 | self.exit_requested.connect(self._do_stop)
39 |
40 | if banner:
41 | self.banner = banner.strip() + '\n\n'
42 |
43 | try:
44 | # noinspection PyUnresolvedReferences
45 | import matplotlib
46 | except ImportError:
47 | pass
48 | else:
49 | self._execute('%matplotlib inline', True)
50 |
51 | def write(self, text):
52 | self._append_plain_text(text, True)
53 |
54 | def flush(self):
55 | pass
56 |
57 | def _do_stop(self):
58 | self.kernel_client.stop_channels()
59 |
60 |
61 | def _make_jupyter_log_handler(target_widget):
62 | def filter_record(record):
63 | name = record.name.lower()
64 | skip = ['ipy', 'jupyter', 'qtconsole']
65 | for s in skip:
66 | if s in name:
67 | return False
68 | return True
69 |
70 | handler = logging.StreamHandler(target_widget)
71 | formatter = logging.Formatter('%(asctime)s %(levelname)s %(name)s: %(message)s')
72 | handler.setFormatter(formatter)
73 | handler.addFilter(filter_record)
74 | return handler
75 |
76 |
77 | class JupyterConsoleWindow(QDialog):
78 | def __init__(self, parent, kernel_manager, banner=None):
79 | super(JupyterConsoleWindow, self).__init__(parent)
80 | self.setAttribute(Qt.WA_DeleteOnClose)
81 | self.setWindowTitle('Jupyter console')
82 |
83 | self._jupyter_widget = JupyterWidget(self, kernel_manager, banner)
84 |
85 | self.on_close = lambda *_: None
86 |
87 | self._log_handler = _make_jupyter_log_handler(self._jupyter_widget)
88 | logging.root.addHandler(self._log_handler)
89 |
90 | self._log_level_selector = QComboBox(self)
91 | self._log_level_selector.setToolTip('Log entries of this severity and higher will appear in the console')
92 | self._log_level_selector.setEditable(False)
93 | self._log_level_selector.addItems(['DEBUG', 'INFO', 'WARNING', 'ERROR', 'CRITICAL'])
94 | self._log_level_selector.currentTextChanged.connect(
95 | lambda: self._log_handler.setLevel(self._log_level_selector.currentText()))
96 | self._log_level_selector.setCurrentIndex(1)
97 |
98 | self._style_selector = QComboBox(self)
99 | self._style_selector.setToolTip('Select standard color theme')
100 | self._style_selector.setEditable(False)
101 | self._style_selector.addItems(['lightbg', 'linux'])
102 | self._style_selector.currentTextChanged.connect(
103 | lambda: self._jupyter_widget.set_default_style(self._style_selector.currentText()))
104 | self._style_selector.setCurrentIndex(0)
105 |
106 | self._redirect_stdout_checkbox = QCheckBox('Redirect stdout', self)
107 | self._redirect_stdout_checkbox.setToolTip('Show stdout output in this console')
108 | self._redirect_stdout_checkbox.stateChanged.connect(self._update_stdout_redirection)
109 | self._redirect_stdout_checkbox.setChecked(True)
110 |
111 | layout = QVBoxLayout(self)
112 | controls_layout = QHBoxLayout(self)
113 | controls_layout.addWidget(QLabel('Log level:', self))
114 | controls_layout.addWidget(self._log_level_selector)
115 | controls_layout.addWidget(QLabel('Color theme:', self))
116 | controls_layout.addWidget(self._style_selector)
117 | controls_layout.addWidget(self._redirect_stdout_checkbox)
118 | controls_layout.addStretch(1)
119 |
120 | layout.addLayout(controls_layout)
121 | layout.addWidget(self._jupyter_widget)
122 | self.setLayout(layout)
123 | self.resize(1000, 600)
124 |
125 | def __del__(self):
126 | self._finalize()
127 |
128 | def _update_stdout_redirection(self):
129 | if self._redirect_stdout_checkbox.isChecked():
130 | sys.stdout = self._jupyter_widget
131 | else:
132 | sys.stdout = sys.__stdout__
133 |
134 | def closeEvent(self, qcloseevent):
135 | self._finalize()
136 | super(JupyterConsoleWindow, self).closeEvent(qcloseevent)
137 | self.on_close()
138 |
139 | def _finalize(self):
140 | sys.stdout = sys.__stdout__
141 | logging.root.removeHandler(self._log_handler)
142 | self._log_handler.close()
143 | logger.info('Jupyter window finalized successfully')
144 |
145 |
146 | class InternalObjectDescriptor:
147 | def __init__(self, name, obj, usage_info):
148 | self.name = name
149 | self.object = obj
150 | self.usage_info = usage_info
151 |
152 |
153 | class ConsoleManager:
154 | def __init__(self, context_provider=None):
155 | """
156 | Args:
157 | context_provider: A callable that returns a list of InternalObjectDescriptor for variables that
158 | will be accessible from the Jupyter console.
159 | """
160 | self._kernel_manager = None
161 | self._context_provider = context_provider or (lambda: [])
162 | self._context = None
163 | self._window = None
164 |
165 | if JUPYTER_AVAILABLE:
166 | # This is sort of experimental. Initialization of a kernel manager takes some time,
167 | # we don't want to do that in the main thread when the application is running. Do something about it.
168 | try:
169 | self._kernel_manager = self._get_kernel_manager()
170 | except Exception:
171 | logger.info('Could not initialize kernel manager', exc_info=True)
172 |
173 | # noinspection PyUnresolvedReferences
174 | def _get_context(self):
175 | # See http://ipython.readthedocs.org/en/stable/api/generated/IPython.core.interactiveshell.html
176 | if self._context is None:
177 | self._context = self._context_provider()
178 |
179 | try:
180 | import matplotlib as mpl
181 | import matplotlib.pyplot as plt
182 | self._context.append(InternalObjectDescriptor('mpl', mpl, 'Imported module "matplotlib"'))
183 | self._context.append(InternalObjectDescriptor('plt', plt, 'Imported module "matplotlib.pyplot"'))
184 | except ImportError:
185 | pass
186 | try:
187 | import numpy as np
188 | self._context.append(InternalObjectDescriptor('np', np, 'Imported module "numpy"'))
189 | except ImportError:
190 | pass
191 | try:
192 | import pylab
193 | self._context.append(InternalObjectDescriptor('pylab', pylab, 'Imported module "pylab"'))
194 | except ImportError:
195 | pass
196 |
197 | import functools
198 | self._context.append(InternalObjectDescriptor('functools', functools, 'Imported module "functools"'))
199 | self._context.append(InternalObjectDescriptor('partial', functools.partial, 'functools.partial'))
200 | self._context.append(InternalObjectDescriptor('reduce', functools.reduce, 'functools.reduce'))
201 |
202 | return self._context
203 |
204 | def _get_kernel_manager(self):
205 | if self._kernel_manager is None:
206 | if not JUPYTER_AVAILABLE:
207 | raise RuntimeError('Jupyter is not available on this system')
208 |
209 | # Initializing the kernel
210 | self._kernel_manager = QtInProcessKernelManager()
211 | self._kernel_manager.start_kernel()
212 | self._kernel_manager.kernel.gui = 'qt'
213 |
214 | # Initializing context
215 | self._kernel_manager.kernel.shell.push({x.name : x.object for x in self._get_context()})
216 |
217 | return self._kernel_manager
218 |
219 | def _make_banner(self):
220 | longest_name = max([len(x.name) for x in self._get_context()])
221 |
222 | banner = 'Available entities:\n'
223 | for obj in self._context:
224 | banner += '\t%- *s -> %s\n' % (longest_name, obj.name, obj.usage_info)
225 |
226 | banner += 'Pydronecan docs: http://dronecan.org/Implementations/Pydronecan\n'
227 | banner += 'DSDL reference: http://dronecan.org/Specification/7._List_of_standard_data_types\n'
228 | return banner
229 |
230 | def show_console_window(self, parent):
231 | if self._window is None:
232 | km = self._get_kernel_manager()
233 | banner = self._make_banner()
234 |
235 | def on_close():
236 | self._window = None
237 |
238 | self._window = JupyterConsoleWindow(parent, km, banner)
239 | self._window.on_close = on_close
240 |
241 | # TODO: Jupyter takes a long time to start up, which may sometimes interfere with the node. Fix it somehow.
242 | # Here, by using the timer we can split the long start-up sequence into two shorter bursts, which kinda helps.
243 | # Ideally, the node should be running in a dedicated thread.
244 | # noinspection PyCallByClass,PyTypeChecker
245 | QTimer.singleShot(50, self._window.show)
246 |
247 | def close(self):
248 | if self._window is not None:
249 | self._window.close()
250 | self._window = None
251 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/directory_selection.py:
--------------------------------------------------------------------------------
1 | from PyQt5.QtWidgets import QGroupBox, QLineEdit, QCompleter, QPushButton, QDirModel, QHBoxLayout, QFileDialog
2 | from PyQt5.QtCore import Qt
3 |
4 | class DirectorySelectionWidget(QGroupBox):
5 | def __init__(self, parent, label, path=None, directory_only=False):
6 | super(DirectorySelectionWidget, self).__init__(label, parent)
7 | self._selection = path
8 | dir_textbox = QLineEdit(self)
9 | dir_textbox.setText(self._selection)
10 |
11 | dir_text_completer = QCompleter(self)
12 | dir_text_completer.setCaseSensitivity(Qt.CaseSensitive)
13 | dir_text_completer.setModel(QDirModel(self))
14 | dir_textbox.setCompleter(dir_text_completer)
15 |
16 | def on_edit():
17 | self._selection = str(dir_textbox.text())
18 |
19 | dir_textbox.textChanged.connect(on_edit)
20 |
21 | dir_browser = QPushButton('Browse', self)
22 |
23 | def on_browse():
24 | if directory_only:
25 | self._selection = str(QFileDialog.getExistingDirectory(self, 'Select Directory'))
26 | else:
27 | self._selection = QFileDialog.getOpenFileName(self, 'Select File')[0]
28 | dir_textbox.setText(self._selection)
29 |
30 | dir_browser.clicked.connect(on_browse)
31 |
32 | layout = QHBoxLayout(self)
33 | layout.addWidget(dir_textbox)
34 | layout.addWidget(dir_browser)
35 | self.setLayout(layout)
36 |
37 | def get_selection(self):
38 | return self._selection
39 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/dynamic_node_id_allocator.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import dronecan
10 | from PyQt5.QtWidgets import QGroupBox, QVBoxLayout, QHBoxLayout, QHeaderView, QPushButton, QFileDialog, \
11 | QCompleter, QDirModel
12 | from PyQt5.QtCore import QTimer
13 | from logging import getLogger
14 | from . import BasicTable, get_monospace_font, get_icon, show_error, CommitableComboBoxWithHistory, make_icon_button
15 |
16 |
17 | logger = getLogger(__name__)
18 |
19 |
20 | def unique_id_to_string(uid):
21 | return ' '.join(['%02X' % x for x in uid]) if uid else 'N/A'
22 |
23 |
24 | class DynamicNodeIDAllocatorWidget(QGroupBox):
25 | DEFAULT_DATABASE_FILE = ':memory:'
26 |
27 | COLUMNS = [
28 | BasicTable.Column('Node ID',
29 | lambda e: e[1]),
30 | BasicTable.Column('Unique ID',
31 | lambda e: unique_id_to_string(e[0]),
32 | resize_mode=QHeaderView.Stretch),
33 | ]
34 |
35 | def __init__(self, parent, node, node_monitor):
36 | super(DynamicNodeIDAllocatorWidget, self).__init__(parent)
37 | self.setTitle('Dynamic node ID allocation server (dronecan.uavcan.protocol.dynamic_node_id.*)')
38 |
39 | self._node = node
40 | self._node_monitor = node_monitor
41 | self._allocator = None
42 |
43 | self._allocation_table = BasicTable(self, self.COLUMNS, font=get_monospace_font())
44 |
45 | self._allocation_table_update_timer = QTimer(self)
46 | self._allocation_table_update_timer.setSingleShot(False)
47 | self._allocation_table_update_timer.start(500)
48 | self._allocation_table_update_timer.timeout.connect(self._update_table)
49 |
50 | self._start_stop_button = make_icon_button('fa6s.rocket', 'Launch/stop the dynamic node ID allocation server', self,
51 | checkable=True)
52 | self._start_stop_button.clicked.connect(self._on_start_stop_button)
53 |
54 | self._database_file = CommitableComboBoxWithHistory(self)
55 | self._database_file.setAcceptDrops(True)
56 | self._database_file.setToolTip('Path to the allocation table file')
57 | self._database_file.setCurrentText(self.DEFAULT_DATABASE_FILE)
58 | self._database_file.addItem(self._database_file.currentText())
59 | self._database_file.on_commit = self._on_start_stop_button
60 |
61 | self._select_database_file = make_icon_button('fa6.folder-open', 'Open allocation table file', self,
62 | on_clicked=self._on_select_database_file)
63 |
64 | db_file_completer = QCompleter()
65 | db_file_completer.setModel(QDirModel(db_file_completer))
66 | self._database_file.setCompleter(db_file_completer)
67 |
68 | self._sync_gui()
69 |
70 | layout = QVBoxLayout(self)
71 |
72 | controls_layout = QHBoxLayout(self)
73 | controls_layout.addWidget(self._start_stop_button)
74 | controls_layout.addWidget(self._database_file, 1)
75 | controls_layout.addWidget(self._select_database_file)
76 |
77 | layout.addLayout(controls_layout)
78 | layout.addWidget(self._allocation_table, 1)
79 | self.setLayout(layout)
80 |
81 | def _on_select_database_file(self):
82 | # TODO: It would be nice to rename the 'Save' button into something more appropriate like 'Open'
83 | dbf = QFileDialog().getSaveFileName(self, 'Select existing database file, or create a new one',
84 | '', '', '', QFileDialog.DontConfirmOverwrite)
85 | self._database_file.setCurrentText(dbf[0])
86 |
87 | def _sync_gui(self):
88 | # Syncing the GUI state
89 | if self._allocator:
90 | self._start_stop_button.setChecked(True)
91 | self.setEnabled(True)
92 | self._database_file.setEnabled(False)
93 | self._select_database_file.setEnabled(False)
94 | else:
95 | self._database_file.setEnabled(True)
96 | self._select_database_file.setEnabled(True)
97 | self._start_stop_button.setChecked(False)
98 | self.setEnabled(not self._node.is_anonymous)
99 |
100 | def _on_start_stop_button(self):
101 | # Serving the start/stop request
102 | if self._allocator:
103 | self._allocator.close()
104 | self._allocator = None
105 | else:
106 | try:
107 | db_file = self._database_file.currentText()
108 | self._allocator = dronecan.app.dynamic_node_id.CentralizedServer(self._node, self._node_monitor,
109 | database_storage=db_file)
110 | except Exception as ex:
111 | show_error('Error', 'Could not start allocator', str(ex), parent=self)
112 |
113 | # Updating the combo box
114 | if self._database_file.findText(self._database_file.currentText()) < 0:
115 | self._database_file.addItem(self._database_file.currentText())
116 |
117 | self._sync_gui()
118 |
119 | def _update_table(self):
120 | self._sync_gui()
121 |
122 | # Redrawing the table
123 | self._allocation_table.setUpdatesEnabled(False)
124 |
125 | if self._allocator is None:
126 | self._allocation_table.setRowCount(0)
127 | else:
128 | known_entries = [] if self._allocator is None else self._allocator.get_allocation_table()
129 | nid_row = {} # map from node ID to its row as the DB can only have one entry per ID
130 |
131 | for row in range(self._allocation_table.rowCount()):
132 | nid_row[int(self._allocation_table.item(row, 0).text())] = row
133 |
134 | def find_insertion_pos_for_node_id(target_nid):
135 | for row in range(self._allocation_table.rowCount()):
136 | nid = int(self._allocation_table.item(row, 0).text())
137 | if nid > target_nid:
138 | return row
139 | return self._allocation_table.rowCount()
140 |
141 | for uid, nid in known_entries:
142 | # compute correct row for this entry
143 | try:
144 | row = nid_row[nid]
145 | except KeyError: # create row if it doesn't exist
146 | row = find_insertion_pos_for_node_id(nid)
147 | self._allocation_table.insertRow(row)
148 | # update later rows
149 | for known_nid, known_row in nid_row.items():
150 | if known_row >= row:
151 | nid_row[known_nid] = known_row + 1
152 |
153 | # update row value if necessary
154 | curr_val = self._allocation_table.item(row, 1)
155 | if curr_val is None or curr_val.text() != unique_id_to_string(uid):
156 | self._allocation_table.set_row(row, (uid, nid))
157 |
158 | self._allocation_table.setUpdatesEnabled(True)
159 |
160 | @property
161 | def allocator(self):
162 | return self._allocator
163 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/file_server.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import dronecan
10 | from dronecan import uavcan
11 | import os
12 | import json
13 | import zlib
14 | import base64
15 | import struct
16 | from PyQt5.QtWidgets import QGroupBox, QVBoxLayout, QHBoxLayout, QWidget, QDirModel, QCompleter, QFileDialog, QLabel
17 | from PyQt5.QtCore import QTimer
18 | from logging import getLogger
19 | from . import make_icon_button, CommitableComboBoxWithHistory, get_icon, flash, LabelWithIcon
20 |
21 |
22 | logger = getLogger(__name__)
23 |
24 | def FileServer_PathKey(path):
25 | '''
26 | return key used in file read request for a path. This is kept to 7 bytes
27 | to keep the read request in 2 frames
28 | '''
29 | ret = base64.b64encode(struct.pack("
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import dronecan
10 | from PyQt5.QtWidgets import QGroupBox, QLabel, QSpinBox, QHBoxLayout, QCheckBox
11 | from PyQt5.QtCore import QTimer
12 | from logging import getLogger
13 | from . import make_icon_button, flash
14 |
15 | logger = getLogger(__name__)
16 |
17 |
18 | NODE_ID_MIN = 1
19 | NODE_ID_MAX = 127
20 |
21 | def setup_filtering(node):
22 | '''setup to filter messages for low bandwidth'''
23 | driver = node.can_driver
24 | ids = []
25 | ids.append(0) # anonymous frames
26 | ids.append(dronecan.uavcan.protocol.NodeStatus.default_dtid)
27 | ids.append(dronecan.uavcan.protocol.GetNodeInfo.default_dtid)
28 | ids.append(dronecan.uavcan.protocol.RestartNode.default_dtid)
29 | ids.append(dronecan.uavcan.protocol.param.GetSet.default_dtid)
30 | ids.append(dronecan.uavcan.protocol.param.ExecuteOpcode.default_dtid)
31 | ids.append(dronecan.uavcan.protocol.file.BeginFirmwareUpdate.default_dtid)
32 | ids.append(dronecan.uavcan.protocol.file.Read.default_dtid)
33 | ids.append(dronecan.uavcan.protocol.file.GetInfo.default_dtid)
34 | ids.append(dronecan.uavcan.protocol.dynamic_node_id.Allocation.default_dtid)
35 | ids.append(dronecan.uavcan.protocol.debug.LogMessage.default_dtid)
36 | ids.append(dronecan.uavcan.tunnel.Targetted.default_dtid)
37 | ids.append(dronecan.dronecan.protocol.Stats.default_dtid)
38 | ids.append(dronecan.dronecan.protocol.CanStats.default_dtid)
39 | logger.info("Setup %u filter IDs" % len(ids))
40 | driver.set_filter_list(ids)
41 |
42 | class LocalNodeWidget(QGroupBox):
43 | def __init__(self, parent, node):
44 | super(LocalNodeWidget, self).__init__(parent)
45 | self.setTitle('Local node properties')
46 |
47 | self._node = node
48 | self._node_id_collector = dronecan.app.message_collector.MessageCollector(
49 | self._node, dronecan.uavcan.protocol.NodeStatus, timeout=dronecan.uavcan.protocol.NodeStatus().OFFLINE_TIMEOUT_MS * 1e-3)
50 |
51 | self._node_id_label = QLabel('Set local node ID:', self)
52 |
53 | self._node_id_spinbox = QSpinBox(self)
54 | self._node_id_spinbox.setMaximum(NODE_ID_MAX)
55 | self._node_id_spinbox.setMinimum(NODE_ID_MIN)
56 | self._node_id_spinbox.setValue(NODE_ID_MAX)
57 | self._node_id_spinbox.valueChanged.connect(self._update)
58 |
59 | self._node_id_apply = make_icon_button('fa6s.hand', 'Apply local node ID', self, text='Set',
60 | on_clicked=self._on_node_id_apply_clicked)
61 |
62 | self._update_timer = QTimer(self)
63 | self._update_timer.setSingleShot(False)
64 | self._update_timer.timeout.connect(self._update)
65 | self._update_timer.start(500)
66 |
67 | self._update()
68 |
69 | layout = QHBoxLayout(self)
70 | layout.addWidget(self._node_id_label)
71 | layout.addWidget(self._node_id_spinbox)
72 | layout.addWidget(self._node_id_apply)
73 |
74 | layout.addStretch(1)
75 |
76 | self.setLayout(layout)
77 |
78 | flash(self, 'Some functions will be unavailable unless local node ID is set')
79 |
80 | def change_bus(self):
81 | '''update bus number'''
82 | self._node.can_driver.set_bus(self._busnum.value())
83 |
84 | def change_filtering(self):
85 | '''update filtering'''
86 | if self._filtering.isChecked():
87 | setup_filtering(self._node)
88 | else:
89 | self._node.can_driver.set_filter_list([])
90 |
91 | def close(self):
92 | self._node_id_collector.close()
93 |
94 | def _update(self):
95 | if not self._node.is_anonymous:
96 | self._node_id_spinbox.setEnabled(False)
97 | self._node_id_spinbox.setValue(self._node.node_id)
98 | self._node_id_apply.hide()
99 | self._node_id_label.setText('Local node ID:')
100 | self._update_timer.stop()
101 | flash(self, 'Local node ID set to %d, all functions should be available now', self._node.node_id)
102 | else:
103 | prohibited_node_ids = set(self._node_id_collector)
104 | while True:
105 | nid = int(self._node_id_spinbox.value())
106 | if not (set(range(nid, NODE_ID_MAX + 1)) - prohibited_node_ids):
107 | self._node_id_spinbox.setValue(nid - 1)
108 | else:
109 | break
110 |
111 | if nid in prohibited_node_ids:
112 | if self._node_id_apply.isEnabled():
113 | self._node_id_apply.setEnabled(False)
114 | flash(self, 'Selected node ID is used by another node, try different one', duration=3)
115 | else:
116 | self._node_id_apply.setEnabled(True)
117 |
118 | def _on_node_id_apply_clicked(self):
119 | nid = int(self._node_id_spinbox.value())
120 | if nid > 0:
121 | self._node.node_id = nid
122 | logger.info('Node ID: %s', self._node.node_id)
123 | self._update()
124 |
125 | class AdapterSettingsWidget(QGroupBox):
126 | def __init__(self, parent, node):
127 | super(AdapterSettingsWidget, self).__init__(parent)
128 | self.setTitle('Adapter Settings')
129 |
130 | self._node = node
131 |
132 | self._canfd_label = QLabel('Send CANFD:', self)
133 | self._canfd = QCheckBox(self)
134 | self._canfd.setTristate(False)
135 | self._canfd.stateChanged.connect(self.change_canfd)
136 |
137 | if node.can_driver.get_bus() is not None:
138 | # allow for changes to mavcan settings
139 | self._busnum_label = QLabel('Bus Number:', self)
140 | self._busnum = QSpinBox(self)
141 | self._busnum.setMaximum(2)
142 | self._busnum.setMinimum(1)
143 | self._busnum.setValue(node.can_driver.get_bus())
144 | self._busnum.valueChanged.connect(self.change_bus)
145 |
146 | self._filtering_label = QLabel('Low Bandwidth:', self)
147 | self._filtering = QCheckBox(self)
148 | self._filtering.setTristate(False)
149 | filter_list = node.can_driver.get_filter_list()
150 | if filter_list is not None and len(filter_list) > 0:
151 | self._filtering.setCheckState(2)
152 | self._filtering.stateChanged.connect(self.change_filtering)
153 |
154 | layout = QHBoxLayout(self)
155 | layout.addWidget(self._canfd_label)
156 | layout.addWidget(self._canfd)
157 |
158 | if node.can_driver.get_bus() is not None:
159 | layout.addWidget(self._busnum_label)
160 | layout.addWidget(self._busnum)
161 | layout.addWidget(self._filtering_label)
162 | layout.addWidget(self._filtering)
163 |
164 | layout.addStretch(1)
165 |
166 | self.setLayout(layout)
167 |
168 | def change_bus(self):
169 | '''update bus number'''
170 | self._node.can_driver.set_bus(self._busnum.value())
171 |
172 | def change_filtering(self):
173 | '''update filtering'''
174 | if self._filtering.isChecked():
175 | setup_filtering(self._node)
176 | else:
177 | self._node.can_driver.set_filter_list([])
178 |
179 | def change_canfd(self):
180 | '''change canfd settings'''
181 | self._node.set_canfd(self._canfd.isChecked())
182 |
183 | def close(self):
184 | pass
185 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/log_message_display.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import dronecan
10 | import datetime
11 | from PyQt5.QtWidgets import QGroupBox, QVBoxLayout, QHBoxLayout, QHeaderView, QPushButton, QLabel
12 | from PyQt5.QtCore import Qt
13 | from logging import getLogger
14 | from . import BasicTable, RealtimeLogWidget
15 |
16 |
17 | logger = getLogger(__name__)
18 |
19 |
20 | def log_level_to_color(level):
21 | return {
22 | level.DEBUG: None,
23 | level.INFO: Qt.green,
24 | level.WARNING: Qt.yellow,
25 | level.ERROR: Qt.red,
26 | }.get(level.value)
27 |
28 |
29 | class LogMessageDisplayWidget(QGroupBox):
30 | COLUMNS = [
31 | BasicTable.Column('NID',
32 | lambda e: e.transfer.source_node_id),
33 | BasicTable.Column('Local Time',
34 | lambda e: datetime.datetime.fromtimestamp(e.transfer.ts_real)
35 | .strftime('%H:%M:%S.%f')[:-3],
36 | searchable=False),
37 | BasicTable.Column('Level',
38 | lambda e: (dronecan.value_to_constant_name(e.message.level, 'value'),
39 | log_level_to_color(e.message.level))),
40 | BasicTable.Column('Source',
41 | lambda e: e.message.source),
42 | BasicTable.Column('Text',
43 | lambda e: e.message.text,
44 | resize_mode=QHeaderView.Stretch),
45 | ]
46 |
47 | def __init__(self, parent, node):
48 | super(LogMessageDisplayWidget, self).__init__(parent)
49 | self.setTitle('Log messages (dronecan.uavcan.protocol.debug.LogMessage)')
50 |
51 | self._log_widget = RealtimeLogWidget(self, columns=self.COLUMNS, multi_line_rows=True, started_by_default=True)
52 | self._log_widget.table.verticalHeader().setSectionResizeMode(QHeaderView.ResizeToContents)
53 | self._log_widget.table.setWordWrap(True)
54 |
55 | self._subscriber = node.add_handler(dronecan.uavcan.protocol.debug.LogMessage, self._log_widget.add_item_async)
56 |
57 | layout = QVBoxLayout(self)
58 | layout.addWidget(self._log_widget, 1)
59 | self.setLayout(layout)
60 |
61 | def close(self):
62 | self._subscriber.remove()
63 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/node_monitor.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import datetime
10 | import dronecan
11 | from . import BasicTable, get_monospace_font
12 | from PyQt5.QtWidgets import QGroupBox, QVBoxLayout, QHeaderView, QLabel
13 | from PyQt5.QtCore import Qt, QTimer, pyqtSignal
14 | from logging import getLogger
15 |
16 |
17 | logger = getLogger(__name__)
18 |
19 | app_node_monitor = None
20 |
21 |
22 | def node_mode_to_color(mode):
23 | s = dronecan.uavcan.protocol.NodeStatus()
24 | return {
25 | s.MODE_INITIALIZATION: Qt.cyan,
26 | s.MODE_MAINTENANCE: Qt.magenta,
27 | s.MODE_SOFTWARE_UPDATE: Qt.magenta,
28 | s.MODE_OFFLINE: Qt.red
29 | }.get(mode)
30 |
31 |
32 | def node_health_to_color(health):
33 | s = dronecan.uavcan.protocol.NodeStatus()
34 | return {
35 | s.HEALTH_WARNING: Qt.yellow,
36 | s.HEALTH_ERROR: Qt.magenta,
37 | s.HEALTH_CRITICAL: Qt.red,
38 | }.get(health)
39 |
40 |
41 | def render_vendor_specific_status_code(s):
42 | out = '%-5d 0x%04x\n' % (s, s)
43 | binary = bin(s)[2:].rjust(16, '0')
44 |
45 | def high_nibble(s):
46 | return s.replace('0', '\u2070').replace('1', '\u00B9') # Unicode 0/1 superscript
47 |
48 | def low_nibble(s):
49 | return s.replace('0', '\u2080').replace('1', '\u2081') # Unicode 0/1 subscript
50 |
51 | nibbles = [
52 | high_nibble(binary[:4]),
53 | low_nibble(binary[4:8]),
54 | high_nibble(binary[8:12]),
55 | low_nibble(binary[12:]),
56 | ]
57 |
58 | out += ''.join(nibbles)
59 | return out
60 |
61 |
62 | class NodeTable(BasicTable):
63 | COLUMNS = [
64 | BasicTable.Column('NID',
65 | lambda e: e.node_id),
66 | BasicTable.Column('Name',
67 | lambda e: e.info.name if e.info else '?',
68 | QHeaderView.Stretch),
69 | BasicTable.Column('Mode',
70 | lambda e: (dronecan.value_to_constant_name(e.status, 'mode'),
71 | node_mode_to_color(e.status.mode))),
72 | BasicTable.Column('Health',
73 | lambda e: (dronecan.value_to_constant_name(e.status, 'health'),
74 | node_health_to_color(e.status.health))),
75 | BasicTable.Column('Uptime',
76 | lambda e: datetime.timedelta(days=0, seconds=e.status.uptime_sec)),
77 | BasicTable.Column('VSSC',
78 | lambda e: render_vendor_specific_status_code(e.status.vendor_specific_status_code))
79 | ]
80 |
81 | info_requested = pyqtSignal([int])
82 |
83 | def __init__(self, parent, node):
84 | super(NodeTable, self).__init__(parent, self.COLUMNS, font=get_monospace_font())
85 |
86 | self.cellDoubleClicked.connect(lambda row, col: self._call_info_requested_callback_on_row(row))
87 | self.on_enter_pressed = self._on_enter
88 |
89 | self._monitor = dronecan.app.node_monitor.NodeMonitor(node)
90 | global app_node_monitor
91 | app_node_monitor = self._monitor
92 |
93 | self._timer = QTimer(self)
94 | self._timer.setSingleShot(False)
95 | self._timer.timeout.connect(self._update)
96 | self._timer.start(500)
97 |
98 | self.setMinimumWidth(600)
99 |
100 | self.verticalHeader().setSectionResizeMode(QHeaderView.ResizeToContents)
101 |
102 | @property
103 | def monitor(self):
104 | return self._monitor
105 |
106 | def close(self):
107 | self._monitor.close()
108 |
109 | def _call_info_requested_callback_on_row(self, row):
110 | nid = int(self.item(row, 0).text())
111 | self.info_requested.emit(nid)
112 |
113 | def _on_enter(self, list_of_row_col_pairs):
114 | unique_rows = set([row for row, _col in list_of_row_col_pairs])
115 | if len(unique_rows) == 1:
116 | self._call_info_requested_callback_on_row(list(unique_rows)[0])
117 |
118 | def _update(self):
119 | known_nodes = {e.node_id: e for e in self._monitor.find_all(lambda _: True)}
120 | displayed_nodes = set()
121 | rows_to_remove = []
122 |
123 | # Updating existing entries
124 | for row in range(self.rowCount()):
125 | nid = int(self.item(row, 0).text())
126 | displayed_nodes.add(nid)
127 | if nid not in known_nodes:
128 | rows_to_remove.append(row)
129 | else:
130 | self.set_row(row, known_nodes[nid])
131 |
132 | # Removing nonexistent entries
133 | for row in rows_to_remove[::-1]: # It is important to traverse from end
134 | logger.info('Removing row %d', row)
135 | self.removeRow(row)
136 |
137 | # Adding new entries
138 | def find_insertion_pos_for_node_id(target_nid):
139 | for row in range(self.rowCount()):
140 | nid = int(self.item(row, 0).text())
141 | if nid > target_nid:
142 | return row
143 | return self.rowCount()
144 |
145 | for nid in set(known_nodes.keys()) - displayed_nodes:
146 | row = find_insertion_pos_for_node_id(nid)
147 | logger.info('Adding new row %d for node %d', row, nid)
148 | self.insertRow(row)
149 | self.set_row(row, known_nodes[nid])
150 |
151 |
152 | class NodeMonitorWidget(QGroupBox):
153 | def __init__(self, parent, node):
154 | super(NodeMonitorWidget, self).__init__(parent)
155 | self.setTitle('Online nodes (double click for more options)')
156 |
157 | self._node = node
158 | self.on_info_window_requested = lambda *_: None
159 |
160 | self._status_update_timer = QTimer(self)
161 | self._status_update_timer.setSingleShot(False)
162 | self._status_update_timer.timeout.connect(self._update_status)
163 | self._status_update_timer.start(500)
164 |
165 | self._table = NodeTable(self, node)
166 | self._table.info_requested.connect(self._show_info_window)
167 |
168 | self._monitor_handle = self._table.monitor.add_update_handler(lambda _: self._update_status())
169 |
170 | self._status_label = QLabel(self)
171 |
172 | vbox = QVBoxLayout(self)
173 | vbox.addWidget(self._table)
174 | vbox.addWidget(self._status_label)
175 | self.setLayout(vbox)
176 |
177 | @property
178 | def monitor(self):
179 | return self._table.monitor
180 |
181 | def close(self):
182 | self._table.close()
183 | self._monitor_handle.remove()
184 | self._status_update_timer.stop()
185 |
186 | def _update_status(self):
187 | if self._node.is_anonymous:
188 | self._status_label.setText('Discovery is not possible - local node is configured in anonymous mode')
189 | else:
190 | num_undiscovered = len(list(self.monitor.find_all(lambda e: not e.discovered)))
191 | if num_undiscovered > 0:
192 | self._status_label.setText('Node discovery is in progress, %d left...' % num_undiscovered)
193 | else:
194 | self._status_label.setText('All nodes are discovered')
195 |
196 | def _show_info_window(self, node_id):
197 | self.on_info_window_requested(node_id)
198 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/__init__.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import os
10 | import sys
11 | import queue
12 | import dronecan
13 | import logging
14 | import multiprocessing
15 | from PyQt5.QtWidgets import QApplication
16 | from PyQt5.QtCore import QTimer
17 | from .window import PlotterWindow
18 |
19 | logger = logging.getLogger(__name__)
20 |
21 | try:
22 | # noinspection PyUnresolvedReferences
23 | sys.getwindowsversion()
24 | RUNNING_ON_WINDOWS = True
25 | except AttributeError:
26 | RUNNING_ON_WINDOWS = False
27 | PARENT_PID = os.getppid()
28 |
29 |
30 | class IPCChannel:
31 | """
32 | This class is built as an abstraction over the underlying IPC communication channel.
33 | """
34 | def __init__(self):
35 | # Queue is slower than pipe, but it allows to implement non-blocking sending easier,
36 | # and the buffer can be arbitrarily large.
37 | self._q = multiprocessing.Queue()
38 |
39 | def send_nonblocking(self, obj):
40 | try:
41 | self._q.put_nowait(obj)
42 | except queue.Full:
43 | pass
44 |
45 | def receive_nonblocking(self):
46 | """Returns: (True, object) if successful, (False, None) if no data to read """
47 | try:
48 | return True, self._q.get_nowait()
49 | except queue.Empty:
50 | return False, None
51 |
52 |
53 | IPC_COMMAND_STOP = 'stop'
54 |
55 |
56 | def _process_entry_point(channel):
57 | logger.info('Plotter process started with PID %r', os.getpid())
58 | app = QApplication(sys.argv) # Inheriting args from the parent process
59 |
60 | def exit_if_should():
61 | if RUNNING_ON_WINDOWS:
62 | return False
63 | else:
64 | return os.getppid() != PARENT_PID # Parent is dead
65 |
66 | exit_check_timer = QTimer()
67 | exit_check_timer.setSingleShot(False)
68 | exit_check_timer.timeout.connect(exit_if_should)
69 | exit_check_timer.start(2000)
70 |
71 | def get_transfer():
72 | received, obj = channel.receive_nonblocking()
73 | if received:
74 | if obj == IPC_COMMAND_STOP:
75 | logger.info('Plotter process has received a stop request, goodbye')
76 | app.exit(0)
77 | else:
78 | return obj
79 |
80 | win = PlotterWindow(get_transfer)
81 | win.show()
82 |
83 | logger.info('Plotter process %r initialized successfully, now starting the event loop', os.getpid())
84 | sys.exit(app.exec_())
85 |
86 |
87 | class CompactMessage:
88 | """
89 | Transfer and message objects from Pydronecan cannot be exchanged between processes,
90 | so we build this minimal representation that is just enough to mimic a Pydronecan message object.
91 | """
92 | def __init__(self, dronecan_data_type_name):
93 | self._dronecan_data_type_name = dronecan_data_type_name
94 | self._fields = {}
95 |
96 | def __repr__(self):
97 | return '%s(%r)' % (self._dronecan_data_type_name, self._fields)
98 |
99 | def _add_field(self, name, value):
100 | self._fields[name] = value
101 |
102 | def __getattr__(self, item):
103 | if item not in ('_fields', '_dronecan_data_type_name'):
104 | try:
105 | return self._fields[item]
106 | except KeyError:
107 | pass
108 | try:
109 | return getattr(dronecan.TYPENAMES[self._dronecan_data_type_name](), item)
110 | except KeyError:
111 | pass
112 | raise AttributeError(item)
113 |
114 |
115 | # noinspection PyProtectedMember
116 | def _extract_struct_fields(m):
117 | if isinstance(m, dronecan.transport.CompoundValue):
118 | out = CompactMessage(dronecan.get_dronecan_data_type(m).full_name)
119 | for field_name, field in dronecan.get_fields(m).items():
120 | if dronecan.is_union(m) and dronecan.get_active_union_field(m) != field_name:
121 | continue
122 | val = _extract_struct_fields(field)
123 | if val is not None:
124 | out._add_field(field_name, val)
125 | return out
126 | elif isinstance(m, dronecan.transport.ArrayValue):
127 | # cannot say I'm breaking the rules
128 | container = bytes if dronecan.get_dronecan_data_type(m).is_string_like else list
129 | # if I can glue them back together
130 | return container(filter(lambda x: x is not None, (_extract_struct_fields(item) for item in m)))
131 | elif isinstance(m, dronecan.transport.PrimitiveValue):
132 | return m.value
133 | elif isinstance(m, (int, float, bool)):
134 | return m
135 | elif isinstance(m, dronecan.transport.VoidValue):
136 | pass
137 | else:
138 | raise ValueError(':(')
139 |
140 |
141 | class MessageTransfer:
142 | def __init__(self, tr):
143 | self.source_node_id = tr.source_node_id
144 | self.ts_mono = tr.ts_monotonic
145 | self.data_type_name = dronecan.get_dronecan_data_type(tr.payload).full_name
146 | self.message = _extract_struct_fields(tr.payload)
147 |
148 |
149 | class PlotterManager:
150 | def __init__(self, node):
151 | self._node = node
152 | self._inferiors = [] # process object, channel
153 | self._hook_handle = None
154 |
155 | def _transfer_hook(self, tr):
156 | if tr.direction == 'rx' and not tr.service_not_message and len(self._inferiors):
157 | msg = MessageTransfer(tr)
158 | for proc, channel in self._inferiors[:]:
159 | if proc.is_alive():
160 | try:
161 | channel.send_nonblocking(msg)
162 | except Exception:
163 | logger.error('Failed to send data to process %r', proc, exc_info=True)
164 | else:
165 | logger.info('Plotter process %r appears to be dead, removing', proc)
166 | self._inferiors.remove((proc, channel))
167 |
168 | def spawn_plotter(self):
169 | channel = IPCChannel()
170 |
171 | if self._hook_handle is None:
172 | self._hook_handle = self._node.add_transfer_hook(self._transfer_hook)
173 |
174 | proc = multiprocessing.Process(target=_process_entry_point, name='plotter', args=(channel,))
175 | proc.daemon = True
176 | proc.start()
177 |
178 | self._inferiors.append((proc, channel))
179 |
180 | logger.info('Spawned new plotter process %r', proc)
181 |
182 | def close(self):
183 | try:
184 | self._hook_handle.remove()
185 | except Exception:
186 | pass
187 |
188 | for _, channel in self._inferiors:
189 | try:
190 | channel.send_nonblocking(IPC_COMMAND_STOP)
191 | except Exception:
192 | pass
193 |
194 | for proc, _ in self._inferiors:
195 | try:
196 | proc.join(1)
197 | except Exception:
198 | pass
199 |
200 | for proc, _ in self._inferiors:
201 | try:
202 | proc.terminate()
203 | except Exception:
204 | pass
205 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/plot_areas/__init__.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | from collections import OrderedDict
10 | from PyQt5.QtGui import QColor
11 | from PyQt5.QtCore import Qt
12 | from pyqtgraph import mkPen, InfiniteLine
13 |
14 |
15 | class AbstractPlotArea:
16 | def add_value(self, extractor, timestamp, value):
17 | pass
18 |
19 | def remove_curves_provided_by_extractor(self, extractor):
20 | pass
21 |
22 | def update(self):
23 | pass
24 |
25 | def reset(self):
26 | pass
27 |
28 |
29 | def add_crosshair(plot, render_measurements, color=Qt.gray):
30 | pen = mkPen(color=QColor(color), width=1)
31 | vline = InfiniteLine(angle=90, movable=False, pen=pen)
32 | hline = InfiniteLine(angle=0, movable=False, pen=pen)
33 |
34 | plot.addItem(vline, ignoreBounds=True)
35 | plot.addItem(hline, ignoreBounds=True)
36 |
37 | current_coordinates = None
38 | reference_coordinates = None
39 |
40 | def do_render():
41 | render_measurements(current_coordinates, reference_coordinates)
42 |
43 | def update(pos):
44 | nonlocal current_coordinates
45 | if plot.sceneBoundingRect().contains(pos):
46 | mouse_point = plot.getViewBox().mapSceneToView(pos)
47 | current_coordinates = mouse_point.x(), mouse_point.y()
48 | vline.setPos(mouse_point.x())
49 | hline.setPos(mouse_point.y())
50 | do_render()
51 |
52 | def set_reference(ev):
53 | nonlocal reference_coordinates
54 | if ev.button() == Qt.LeftButton and current_coordinates is not None:
55 | reference_coordinates = current_coordinates
56 | do_render()
57 |
58 | plot.scene().sigMouseMoved.connect(update)
59 | plot.scene().sigMouseClicked.connect(set_reference)
60 |
61 |
62 | from .yt import PlotAreaYTWidget
63 | from .xy import PlotAreaXYWidget
64 |
65 | PLOT_AREAS = OrderedDict([
66 | ('Y-T plot', PlotAreaYTWidget),
67 | ('X-Y plot', PlotAreaXYWidget),
68 | ])
69 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/plot_areas/xy.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import math
10 | import logging
11 | from PyQt5.QtWidgets import QWidget, QVBoxLayout, QHBoxLayout, QSpinBox, QComboBox, QLabel, QCheckBox, QDoubleSpinBox
12 | from PyQt5.QtGui import QColor
13 | from PyQt5.QtCore import Qt
14 | from pyqtgraph import PlotWidget, mkPen
15 | from . import AbstractPlotArea, add_crosshair
16 | from ... import make_icon_button
17 |
18 |
19 | logger = logging.getLogger(__name__)
20 |
21 |
22 | class AbstractPlotContainer:
23 | def __init__(self, plot):
24 | self.plot = plot
25 | self.x = []
26 | self.y = []
27 |
28 | def add_point(self, x, y, max_data_points):
29 | while len(self.x) >= max_data_points:
30 | self.x.pop(0)
31 | self.y.pop(0)
32 | assert len(self.x) == len(self.y)
33 | self.x.append(x)
34 | self.y.append(y)
35 |
36 | def update(self):
37 | self.plot.setData(self.x, self.y)
38 |
39 |
40 | class LinePlotContainer(AbstractPlotContainer):
41 | def __init__(self, plot, pen):
42 | super(LinePlotContainer, self).__init__(plot)
43 | self.pen = pen
44 |
45 | def set_color(self, color):
46 | self.pen.setColor(color)
47 | self.plot.setPen(self.pen)
48 |
49 |
50 | class ScatterPlotContainer(AbstractPlotContainer):
51 | def __init__(self, parent, color):
52 | self.parent = parent
53 | super(ScatterPlotContainer, self).__init__(self._inst(color))
54 |
55 | def _inst(self, color):
56 | return self.parent.scatterPlot(symbol='+', size=2, pen=mkPen(color=color, width=1))
57 |
58 | def set_color(self, color):
59 | # We have to re-create the plot from scratch, because seems to be impossible to re-color a ScatterPlot
60 | # once it has been created. Either it's bug in PyQtGraph, or I'm doing something wrong.
61 | self.parent.removeItem(self.plot)
62 | self.plot = self._inst(color)
63 |
64 |
65 | class PlotAreaXYWidget(QWidget, AbstractPlotArea):
66 | def __init__(self, parent, display_measurements):
67 | super(PlotAreaXYWidget, self).__init__(parent)
68 |
69 | self._extractor_associations = {} # Extractor : plot
70 |
71 | self._clear_button = make_icon_button('fa6s.eraser', 'Clear all plots', self, on_clicked=self.reset)
72 |
73 | self._max_data_points = 100000
74 |
75 | self._max_data_points_spinbox = QSpinBox(self)
76 | self._max_data_points_spinbox.setMinimum(1)
77 | self._max_data_points_spinbox.setMaximum(1000000)
78 | self._max_data_points_spinbox.setValue(self._max_data_points)
79 | self._max_data_points_spinbox.valueChanged.connect(self._update_max_data_points)
80 |
81 | self._plot_mode_box = QComboBox(self)
82 | self._plot_mode_box.setEditable(False)
83 | self._plot_mode_box.addItems(['Line', 'Scatter'])
84 | self._plot_mode_box.setCurrentIndex(0)
85 | self._plot_mode_box.currentTextChanged.connect(self.reset)
86 |
87 | self._lock_aspect_ratio_checkbox = QCheckBox('Lock aspect ratio:', self)
88 | self._lock_aspect_ratio_checkbox.setChecked(True)
89 |
90 | self._aspect_ratio_spinbox = QDoubleSpinBox(self)
91 | self._aspect_ratio_spinbox.setMinimum(1e-3)
92 | self._aspect_ratio_spinbox.setMaximum(1e+3)
93 | self._aspect_ratio_spinbox.setDecimals(3)
94 | self._aspect_ratio_spinbox.setValue(1)
95 | self._aspect_ratio_spinbox.setSingleStep(0.1)
96 |
97 | self._lock_aspect_ratio_checkbox.clicked.connect(self._update_aspect_ratio)
98 | self._aspect_ratio_spinbox.valueChanged.connect(self._update_aspect_ratio)
99 |
100 | self._plot = PlotWidget(self, background=QColor(Qt.black))
101 | self._plot.showButtons()
102 | self._plot.enableAutoRange()
103 | self._plot.showGrid(x=True, y=True, alpha=0.4)
104 |
105 | layout = QVBoxLayout(self)
106 | layout.addWidget(self._plot, 1)
107 |
108 | controls_layout = QHBoxLayout(self)
109 | controls_layout.addWidget(self._clear_button)
110 | controls_layout.addStretch(1)
111 | controls_layout.addWidget(QLabel('Points per plot:', self))
112 | controls_layout.addWidget(self._max_data_points_spinbox)
113 | controls_layout.addWidget(QLabel('Style:', self))
114 | controls_layout.addWidget(self._plot_mode_box)
115 | controls_layout.addWidget(self._lock_aspect_ratio_checkbox)
116 | controls_layout.addWidget(self._aspect_ratio_spinbox)
117 |
118 | layout.addLayout(controls_layout)
119 | layout.setContentsMargins(0, 0, 0, 0)
120 | self.setLayout(layout)
121 |
122 | # Crosshair
123 | def _render_measurements(cur, ref):
124 | text = 'x %.6f, y %.6f' % cur
125 | if ref is None:
126 | return text
127 | dx = cur[0] - ref[0]
128 | dy = cur[1] - ref[1]
129 | dist = math.sqrt(dx ** 2 + dy ** 2)
130 | text += ';' + ' ' * 4 + 'dx %.6f, dy %.6f, dist %.6f' % (dx, dy, dist)
131 | display_measurements(text)
132 |
133 | display_measurements('Hover to sample X/Y, click to set new reference')
134 | add_crosshair(self._plot, _render_measurements)
135 |
136 | # Initialization
137 | self._update_aspect_ratio()
138 | self._update_max_data_points()
139 |
140 | def _update_max_data_points(self):
141 | self._max_data_points = self._max_data_points_spinbox.value()
142 |
143 | def _update_aspect_ratio(self):
144 | if self._lock_aspect_ratio_checkbox.isChecked():
145 | self._aspect_ratio_spinbox.setEnabled(True)
146 | self._plot.setAspectLocked(True, ratio=self._aspect_ratio_spinbox.value())
147 | else:
148 | self._aspect_ratio_spinbox.setEnabled(False)
149 | self._plot.setAspectLocked(False)
150 |
151 | def _forge_curve(self, color):
152 | logger.info('Adding new curve')
153 |
154 | mode = self._plot_mode_box.currentText().lower()
155 | if mode == 'line':
156 | return LinePlotContainer(self._plot.plot(), mkPen(color=color, width=1))
157 | elif mode == 'scatter':
158 | return ScatterPlotContainer(self._plot, color)
159 | else:
160 | raise RuntimeError('Invalid plot mode: %r' % mode)
161 |
162 | def add_value(self, extractor, _timestamp, xy):
163 | try:
164 | x, y = xy
165 | except Exception:
166 | if extractor in self._extractor_associations:
167 | self.remove_curves_provided_by_extractor(extractor)
168 | raise RuntimeError('XY must be an iterable with exactly 2 elements')
169 |
170 | if extractor not in self._extractor_associations:
171 | self._extractor_associations[extractor] = self._forge_curve(extractor.color)
172 |
173 | self._extractor_associations[extractor].add_point(float(x), float(y), self._max_data_points)
174 | self._extractor_associations[extractor].set_color(extractor.color)
175 |
176 | def remove_curves_provided_by_extractor(self, extractor):
177 | self._plot.removeItem(self._extractor_associations[extractor].plot)
178 | del self._extractor_associations[extractor]
179 |
180 | def _do_clear(self):
181 | for k in list(self._extractor_associations.keys()):
182 | self.remove_curves_provided_by_extractor(k)
183 |
184 | def reset(self):
185 | self._do_clear()
186 | self._plot.enableAutoRange()
187 |
188 | def update(self):
189 | for c in self._extractor_associations.values():
190 | c.update()
191 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/plot_areas/yt.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import logging
10 | from PyQt5.QtWidgets import QWidget, QVBoxLayout, QHBoxLayout
11 | from PyQt5.QtGui import QColor
12 | from PyQt5.QtCore import Qt
13 | from pyqtgraph import PlotWidget, mkPen
14 | from . import AbstractPlotArea, add_crosshair
15 | from ... import make_icon_button
16 |
17 |
18 | logger = logging.getLogger(__name__)
19 |
20 |
21 | class CurveContainer:
22 | MAX_DATA_POINTS = 200000
23 |
24 | def __init__(self, plot, base_color, darkening, pen):
25 | self.base_color = base_color
26 | self.darkening = darkening
27 | self.pen = pen
28 | self.plot = plot
29 | self.x = []
30 | self.y = []
31 |
32 | def add_point(self, x, y):
33 | while len(self.x) >= self.MAX_DATA_POINTS:
34 | self.x.pop(0)
35 | self.y.pop(0)
36 | assert len(self.x) == len(self.y)
37 | self.x.append(x)
38 | self.y.append(y)
39 |
40 | def set_color(self, color):
41 | if self.base_color != color:
42 | self.base_color = color
43 | color = self.base_color.darker(self.darkening)
44 | logger.info('Updating color %r --> %r', self.pen.color(), color)
45 | self.pen.setColor(color)
46 |
47 | def update(self):
48 | self.plot.setData(self.x, self.y, pen=self.pen)
49 |
50 |
51 | class PlotAreaYTWidget(QWidget, AbstractPlotArea):
52 | INITIAL_X_RANGE = 120
53 | MAX_CURVES_PER_EXTRACTOR = 9
54 |
55 | def __init__(self, parent, display_measurements):
56 | super(PlotAreaYTWidget, self).__init__(parent)
57 |
58 | self._extractor_associations = {} # Extractor : plots
59 | self._max_x = 0
60 |
61 | self._autoscroll_checkbox = make_icon_button('fa6s.angles-right',
62 | 'Scroll the plot automatically as new data arrives', self,
63 | checkable=True, checked=True)
64 |
65 | self._clear_button = make_icon_button('fa6s.eraser', 'Clear all curves', self, on_clicked=self._do_clear)
66 |
67 | self._plot = PlotWidget(self, background=QColor(Qt.black))
68 | self._plot.showButtons()
69 | self._plot.enableAutoRange()
70 | self._plot.showGrid(x=True, y=True, alpha=0.4)
71 | self._legend = None
72 | # noinspection PyArgumentList
73 | self._plot.setRange(xRange=(0, self.INITIAL_X_RANGE), padding=0)
74 |
75 | layout = QHBoxLayout(self)
76 |
77 | controls_layout = QVBoxLayout(self)
78 | controls_layout.addWidget(self._clear_button)
79 | controls_layout.addWidget(self._autoscroll_checkbox)
80 | controls_layout.addStretch(1)
81 | layout.addLayout(controls_layout)
82 |
83 | layout.addWidget(self._plot, 1)
84 |
85 | layout.setContentsMargins(0, 0, 0, 0)
86 | self.setLayout(layout)
87 |
88 | # Crosshair
89 | def _render_measurements(cur, ref):
90 | text = 'time %.6f sec, y %.6f' % cur
91 | if ref is None:
92 | return text
93 | dt = cur[0] - ref[0]
94 | dy = cur[1] - ref[1]
95 | if abs(dt) > 1e-12:
96 | freq = '%.6f' % abs(1 / dt)
97 | else:
98 | freq = 'inf'
99 | display_measurements(text + ';' + ' ' * 4 + 'dt %.6f sec, freq %s Hz, dy %.6f' % (dt, freq, dy))
100 |
101 | display_measurements('Hover to sample Time/Y, click to set new reference')
102 | add_crosshair(self._plot, _render_measurements)
103 |
104 | def _forge_curves(self, how_many, base_color):
105 | if how_many > 1 and self._legend is None:
106 | self._legend = self._plot.addLegend()
107 |
108 | out = []
109 | darkening_values = [100, 200, 300]
110 | dash_patterns = (
111 | [],
112 | [3, 3],
113 | [10, 3]
114 | )
115 | for idx in range(how_many):
116 | logger.info('Adding new curve')
117 | try:
118 | darkening = darkening_values[idx % len(darkening_values)]
119 | pattern = dash_patterns[int(idx / len(darkening_values)) % len(dash_patterns)]
120 | pen = mkPen(color=base_color.darker(darkening), width=1, dash=pattern)
121 | plot = self._plot.plot(name=str(idx), pen=pen)
122 | out.append(CurveContainer(plot, base_color, darkening, pen))
123 | except Exception:
124 | logger.error('Could not add curve', exc_info=True)
125 | return out
126 |
127 | def add_value(self, extractor, x, y):
128 | try:
129 | num_curves = len(y)
130 | except Exception:
131 | num_curves = 1
132 | y = y, # do you love Python as I do
133 |
134 | # If number of curves changed, removing all plots from this extractor
135 | if extractor in self._extractor_associations and num_curves != len(self._extractor_associations[extractor]):
136 | self.remove_curves_provided_by_extractor(extractor)
137 |
138 | # Creating curves if needed
139 | if extractor not in self._extractor_associations:
140 | # Techincally, we can plot as many curves as you want, but large number may indicate that smth is wrong
141 | if num_curves > self.MAX_CURVES_PER_EXTRACTOR:
142 | raise RuntimeError('%r curves is much too many' % num_curves)
143 | self._extractor_associations[extractor] = self._forge_curves(num_curves, extractor.color)
144 |
145 | # Actually plotting
146 | for idx, curve in enumerate(self._extractor_associations[extractor]):
147 | curve.add_point(x, float(y[idx]))
148 | curve.set_color(extractor.color)
149 |
150 | # Updating the rightmost value
151 | self._max_x = max(self._max_x, x)
152 |
153 | def remove_curves_provided_by_extractor(self, extractor):
154 | try:
155 | curves = self._extractor_associations[extractor]
156 | del self._extractor_associations[extractor]
157 | for c in curves:
158 | self._plot.removeItem(c.plot)
159 | except KeyError:
160 | pass
161 |
162 | if self._legend is not None:
163 | self._legend.scene().removeItem(self._legend)
164 | self._legend = None
165 |
166 | def _do_clear(self):
167 | for k in list(self._extractor_associations.keys()):
168 | self.remove_curves_provided_by_extractor(k)
169 |
170 | def reset(self):
171 | self._do_clear()
172 | self._max_x = 0
173 | self._plot.enableAutoRange()
174 | # noinspection PyArgumentList
175 | self._plot.setRange(xRange=(0, self.INITIAL_X_RANGE), padding=0)
176 |
177 | def update(self):
178 | # Updating curves
179 | for curves in self._extractor_associations.values():
180 | for c in curves:
181 | c.update()
182 |
183 | # Updating view range
184 | if self._autoscroll_checkbox.isChecked():
185 | (xmin, xmax), _ = self._plot.viewRange()
186 | diff = xmax - xmin
187 | xmax = self._max_x
188 | xmin = self._max_x - diff
189 | # noinspection PyArgumentList
190 | self._plot.setRange(xRange=(xmin, xmax), padding=0)
191 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/plot_container.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import logging
10 | from PyQt5.QtWidgets import QDockWidget, QVBoxLayout, QHBoxLayout, QWidget, QLabel
11 | from PyQt5.QtCore import Qt
12 | from .. import make_icon_button
13 | from .value_extractor_views import NewValueExtractorWindow, ExtractorWidget
14 |
15 |
16 | logger = logging.getLogger(__name__)
17 |
18 |
19 | class PlotContainerWidget(QDockWidget):
20 | def __init__(self, parent, plot_area_class, active_data_types):
21 | super(PlotContainerWidget, self).__init__(parent)
22 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
23 |
24 | self.on_close = lambda: None
25 |
26 | self._plot_area = plot_area_class(self, display_measurements=self.setWindowTitle)
27 |
28 | self.update = self._plot_area.update
29 | self.reset = self._plot_area.reset
30 |
31 | self._active_data_types = active_data_types
32 | self._extractors = []
33 |
34 | self._new_extractor_button = make_icon_button('fa6s.plus', 'Add new value extractor', self,
35 | on_clicked=self._do_new_extractor)
36 |
37 | self._how_to_label = QLabel('\u27F5 Click to configure plotting', self)
38 |
39 | widget = QWidget(self)
40 |
41 | layout = QVBoxLayout(widget)
42 | layout.addWidget(self._plot_area, 1)
43 |
44 | footer_layout = QHBoxLayout(self)
45 |
46 | controls_layout = QVBoxLayout(widget)
47 | controls_layout.addWidget(self._new_extractor_button)
48 | controls_layout.addStretch(1)
49 | controls_layout.setContentsMargins(0, 0, 0, 0)
50 | footer_layout.addLayout(controls_layout)
51 | footer_layout.addWidget(self._how_to_label)
52 |
53 | self._extractors_layout = QVBoxLayout(widget)
54 | self._extractors_layout.setContentsMargins(0, 0, 0, 0)
55 | footer_layout.addLayout(self._extractors_layout, 1)
56 |
57 | footer_layout.setContentsMargins(0, 0, 0, 0)
58 | layout.addLayout(footer_layout)
59 | widget.setLayout(layout)
60 |
61 | self.setWidget(widget)
62 | self.setFeatures(QDockWidget.DockWidgetFloatable |
63 | QDockWidget.DockWidgetClosable |
64 | QDockWidget.DockWidgetMovable)
65 |
66 | self.setMinimumWidth(700)
67 | self.setMinimumHeight(400)
68 |
69 | def _do_new_extractor(self):
70 | if self._how_to_label is not None:
71 | self._how_to_label.hide()
72 | self._how_to_label.setParent(None)
73 | self._how_to_label.deleteLater()
74 | self._how_to_label = None
75 |
76 | def done(extractor):
77 | self._extractors.append(extractor)
78 | widget = ExtractorWidget(self, extractor)
79 | self._extractors_layout.addWidget(widget)
80 |
81 | def remove():
82 | self._plot_area.remove_curves_provided_by_extractor(extractor)
83 | self._extractors.remove(extractor)
84 | self._extractors_layout.removeWidget(widget)
85 |
86 | widget.on_remove = remove
87 |
88 | win = NewValueExtractorWindow(self, self._active_data_types)
89 | win.on_done = done
90 | win.show()
91 |
92 | def process_transfer(self, timestamp, tr):
93 | for extractor in self._extractors:
94 | try:
95 | value = extractor.try_extract(tr)
96 | if value is None:
97 | continue
98 | self._plot_area.add_value(extractor, timestamp, value)
99 | except Exception:
100 | extractor.register_error()
101 |
102 | def closeEvent(self, qcloseevent):
103 | super(PlotContainerWidget, self).closeEvent(qcloseevent)
104 | self.on_close()
105 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/value_extractor.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 |
10 | EXPRESSION_VARIABLE_FOR_MESSAGE = 'msg'
11 | EXPRESSION_VARIABLE_FOR_SRC_NODE_ID = 'src_node_id'
12 |
13 |
14 | class Expression:
15 | class EvaluationError(Exception):
16 | pass
17 |
18 | def __init__(self, source=None):
19 | self._source = None
20 | self._compiled = None
21 | self.set(source)
22 |
23 | def set(self, source):
24 | source = source.strip()
25 | code = compile(str(source), '', 'eval') # May throw
26 | self._source = source
27 | self._compiled = code
28 |
29 | @property
30 | def source(self):
31 | return self._source
32 |
33 | # noinspection PyShadowingBuiltins
34 | def evaluate(self, **locals):
35 | try:
36 | return eval(self._compiled, globals(), locals)
37 | except Exception as ex:
38 | raise self.EvaluationError('Failed to evaluate expression: %s' % ex) from ex
39 |
40 |
41 | class Extractor:
42 | def __init__(self, data_type_name, extraction_expression, filter_expressions, color):
43 | self.data_type_name = data_type_name
44 | self.extraction_expression = extraction_expression
45 | self.filter_expressions = filter_expressions
46 | self.color = color
47 | self._error_count = 0
48 |
49 | def __repr__(self):
50 | return '%r %r %r' % (self.data_type_name, self.extraction_expression.source,
51 | [x.source for x in self.filter_expressions])
52 |
53 | def try_extract(self, tr):
54 | if tr.data_type_name != self.data_type_name:
55 | return
56 |
57 | evaluation_kwargs = {
58 | EXPRESSION_VARIABLE_FOR_MESSAGE: tr.message,
59 | EXPRESSION_VARIABLE_FOR_SRC_NODE_ID: tr.source_node_id,
60 | }
61 |
62 | for exp in self.filter_expressions:
63 | if not exp.evaluate(**evaluation_kwargs):
64 | return
65 |
66 | value = self.extraction_expression.evaluate(**evaluation_kwargs)
67 |
68 | return value
69 |
70 | def register_error(self):
71 | self._error_count += 1
72 |
73 | def reset_error_count(self):
74 | self._error_count = 0
75 |
76 | @property
77 | def error_count(self):
78 | return self._error_count
79 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/plotter/window.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import time
10 | import logging
11 | from functools import partial
12 | from PyQt5.QtWidgets import QMainWindow, QWidget, QVBoxLayout, QAction
13 | from PyQt5.QtCore import QTimer, Qt
14 | from PyQt5.QtGui import QKeySequence
15 | from .. import get_app_icon, get_icon
16 | from .plot_areas import PLOT_AREAS
17 | from .plot_container import PlotContainerWidget
18 |
19 |
20 | logger = logging.getLogger(__name__)
21 |
22 |
23 | class PlotterWindow(QMainWindow):
24 | def __init__(self, get_transfer_callback):
25 | super(PlotterWindow, self).__init__()
26 | self.setWindowTitle('DroneCAN Plotter')
27 | self.setWindowIcon(get_app_icon())
28 |
29 | self._active_data_types = set()
30 |
31 | self._get_transfer = get_transfer_callback
32 |
33 | self._update_timer = QTimer(self)
34 | self._update_timer.setSingleShot(False)
35 | self._update_timer.timeout.connect(self._update)
36 | self._update_timer.start(50)
37 |
38 | self._base_time = time.monotonic()
39 |
40 | self._plot_containers = []
41 |
42 | #
43 | # Control menu
44 | #
45 | control_menu = self.menuBar().addMenu('&Control')
46 |
47 | self._stop_action = QAction(get_icon('fa6s.stop'), '&Stop Updates', self)
48 | self._stop_action.setStatusTip('While stopped, all new data will be discarded')
49 | self._stop_action.setShortcut(QKeySequence('Ctrl+Shift+S'))
50 | self._stop_action.setCheckable(True)
51 | self._stop_action.toggled.connect(self._on_stop_toggled)
52 | control_menu.addAction(self._stop_action)
53 |
54 | self._pause_action = QAction(get_icon('fa6s.pause'), '&Pause Updates', self)
55 | self._pause_action.setStatusTip('While paused, new data will be accumulated in memory '
56 | 'to be processed once un-paused')
57 | self._pause_action.setShortcut(QKeySequence('Ctrl+Shift+P'))
58 | self._pause_action.setCheckable(True)
59 | self._pause_action.toggled.connect(self._on_pause_toggled)
60 | control_menu.addAction(self._pause_action)
61 |
62 | control_menu.addSeparator()
63 |
64 | self._reset_time_action = QAction(get_icon('fa6s.clock-rotate-left'), '&Reset', self)
65 | self._reset_time_action.setStatusTip('Base time will be reset; all plots will be reset')
66 | self._reset_time_action.setShortcut(QKeySequence('Ctrl+Shift+R'))
67 | self._reset_time_action.triggered.connect(self._do_reset)
68 | control_menu.addAction(self._reset_time_action)
69 |
70 | #
71 | # New Plot menu
72 | #
73 | plot_menu = self.menuBar().addMenu('&New Plot')
74 | for idx, pl_name in enumerate(PLOT_AREAS.keys()):
75 | new_plot_action = QAction('Add ' + pl_name, self)
76 | new_plot_action.setStatusTip('Add new plot window')
77 | new_plot_action.setShortcut(QKeySequence('Ctrl+Alt+' + str(idx)))
78 | new_plot_action.triggered.connect(partial(self._do_add_new_plot, pl_name))
79 | plot_menu.addAction(new_plot_action)
80 |
81 | #
82 | # Window stuff
83 | #
84 | self.statusBar().showMessage('Use the "New Plot" menu to add plots')
85 | self.setCentralWidget(None)
86 | self.resize(600, 400)
87 |
88 | def _on_stop_toggled(self, checked):
89 | self._pause_action.setChecked(False)
90 | self.statusBar().showMessage('Stopped' if checked else 'Un-stopped')
91 |
92 | def _on_pause_toggled(self, checked):
93 | self.statusBar().showMessage('Paused' if checked else 'Un-paused')
94 |
95 | def _do_add_new_plot(self, plot_area_name):
96 | def remove():
97 | self._plot_containers.remove(plc)
98 |
99 | plc = PlotContainerWidget(self, PLOT_AREAS[plot_area_name], self._active_data_types)
100 | plc.on_close = remove
101 | self._plot_containers.append(plc)
102 |
103 | docks = [
104 | Qt.LeftDockWidgetArea,
105 | Qt.LeftDockWidgetArea,
106 | Qt.RightDockWidgetArea,
107 | Qt.RightDockWidgetArea,
108 | ]
109 | dock_to = docks[(len(self._plot_containers) - 1) % len(docks)]
110 | self.addDockWidget(dock_to, plc)
111 |
112 | if len(self._plot_containers) > 1:
113 | self.statusBar().showMessage('Drag plots by the header to rearrange or detach them')
114 |
115 | def _do_reset(self):
116 | self._base_time = time.monotonic()
117 |
118 | for plc in self._plot_containers:
119 | try:
120 | plc.reset()
121 | except Exception:
122 | logger.error('Failed to reset plot container', exc_info=True)
123 |
124 | logger.info('Reset done, new time base %r', self._base_time)
125 |
126 | def _update(self):
127 | if self._stop_action.isChecked():
128 | while self._get_transfer() is not None: # Discarding everything
129 | pass
130 | return
131 |
132 | if not self._pause_action.isChecked():
133 | while True:
134 | tr = self._get_transfer()
135 | if not tr:
136 | break
137 |
138 | self._active_data_types.add(tr.data_type_name)
139 |
140 | for plc in self._plot_containers:
141 | try:
142 | plc.process_transfer(tr.ts_mono - self._base_time, tr)
143 | except Exception:
144 | logger.error('Plot container failed to process a transfer', exc_info=True)
145 |
146 | for plc in self._plot_containers:
147 | try:
148 | plc.update()
149 | except Exception:
150 | logger.error('Plot container failed to update', exc_info=True)
151 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/subscriber.py:
--------------------------------------------------------------------------------
1 | #
2 | # Copyright (C) 2016 UAVCAN Development Team
3 | #
4 | # This software is distributed under the terms of the MIT License.
5 | #
6 | # Author: Pavel Kirienko
7 | #
8 |
9 | import time
10 | import dronecan
11 | import logging
12 | import queue
13 | from PyQt5.QtWidgets import QWidget, QDialog, QPlainTextEdit, QSpinBox, QHBoxLayout, QVBoxLayout, QComboBox, \
14 | QCompleter, QLabel
15 | from PyQt5.QtCore import Qt, QTimer
16 | from . import CommitableComboBoxWithHistory, make_icon_button, get_monospace_font, show_error, FilterBar
17 |
18 |
19 | logger = logging.getLogger(__name__)
20 |
21 |
22 | class QuantityDisplay(QWidget):
23 | def __init__(self, parent, quantity_name, units_of_measurement):
24 | super(QuantityDisplay, self).__init__(parent)
25 |
26 | self._label = QLabel('?', self)
27 |
28 | layout = QHBoxLayout(self)
29 | layout.addStretch(1)
30 | layout.addWidget(QLabel(quantity_name, self))
31 | layout.addWidget(self._label)
32 | layout.addWidget(QLabel(units_of_measurement, self))
33 | layout.addStretch(1)
34 | layout.setContentsMargins(0, 0, 0, 0)
35 | self.setLayout(layout)
36 |
37 | def set(self, value):
38 | self._label.setText(str(value))
39 |
40 |
41 | class RateEstimator:
42 | def __init__(self, update_interval=0.5, averaging_period=4):
43 | self._update_interval = update_interval
44 | self._estimate_lifetime = update_interval * averaging_period
45 | self._averaging_period = averaging_period
46 | self._hist = []
47 | self._checkpoint_ts = 0
48 | self._events_since_checkpoint = 0
49 | self._estimate_expires_at = time.monotonic()
50 |
51 | def register_event(self, timestamp):
52 | self._events_since_checkpoint += 1
53 |
54 | dt = timestamp - self._checkpoint_ts
55 | if dt >= self._update_interval:
56 | # Resetting the stat if expired
57 | mono_ts = time.monotonic()
58 | expired = mono_ts > self._estimate_expires_at
59 | self._estimate_expires_at = mono_ts + self._estimate_lifetime
60 | if expired:
61 | self._hist = []
62 | elif len(self._hist) >= self._averaging_period:
63 | self._hist.pop()
64 | # Updating the history
65 | self._hist.insert(0, self._events_since_checkpoint / dt)
66 | self._checkpoint_ts = timestamp
67 | self._events_since_checkpoint = 0
68 |
69 | def get_rate_with_timestamp(self):
70 | if time.monotonic() <= self._estimate_expires_at:
71 | return (sum(self._hist) / len(self._hist)), self._checkpoint_ts
72 |
73 |
74 | class SubscriberWindow(QDialog):
75 | WINDOW_NAME_PREFIX = 'Subscriber'
76 |
77 | def __init__(self, parent, node, active_data_type_detector):
78 | super(SubscriberWindow, self).__init__(parent)
79 | self.setWindowTitle(self.WINDOW_NAME_PREFIX)
80 | self.setAttribute(Qt.WA_DeleteOnClose) # This is required to stop background timers!
81 |
82 | self._node = node
83 | self._active_data_type_detector = active_data_type_detector
84 | self._active_data_type_detector.message_types_updated.connect(self._update_data_type_list)
85 |
86 | self._message_queue = queue.Queue()
87 |
88 | self._subscriber_handle = None
89 |
90 | self._update_timer = QTimer(self)
91 | self._update_timer.setSingleShot(False)
92 | self._update_timer.timeout.connect(self._do_redraw)
93 | self._update_timer.start(100)
94 |
95 | self._log_viewer = QPlainTextEdit(self)
96 | self._log_viewer.setReadOnly(True)
97 | self._log_viewer.setLineWrapMode(QPlainTextEdit.NoWrap)
98 | self._log_viewer.setFont(get_monospace_font())
99 | self._log_viewer.setVerticalScrollBarPolicy(Qt.ScrollBarAlwaysOn)
100 | try:
101 | self._log_viewer.setPlaceholderText('Received messages will be printed here in YAML format')
102 | except AttributeError: # Old PyQt
103 | pass
104 |
105 | self._num_rows_spinbox = QSpinBox(self)
106 | self._num_rows_spinbox.setToolTip('Number of rows to display; large number will impair performance')
107 | self._num_rows_spinbox.valueChanged.connect(
108 | lambda: self._log_viewer.setMaximumBlockCount(self._num_rows_spinbox.value()))
109 | self._num_rows_spinbox.setMinimum(1)
110 | self._num_rows_spinbox.setMaximum(1000000)
111 | self._num_rows_spinbox.setValue(100)
112 |
113 | self._num_errors = 0
114 | self._num_messages_total = 0
115 | self._num_messages_past_filter = 0
116 |
117 | self._msgs_per_sec_estimator = RateEstimator()
118 |
119 | self._num_messages_total_label = QuantityDisplay(self, 'Total', 'msgs')
120 | self._num_messages_past_filter_label = QuantityDisplay(self, 'Accepted', 'msgs')
121 | self._msgs_per_sec_label = QuantityDisplay(self, 'Accepting', 'msg/sec')
122 |
123 | self._type_selector = CommitableComboBoxWithHistory(self)
124 | self._type_selector.setToolTip('Name of the message type to subscribe to')
125 | self._type_selector.setInsertPolicy(QComboBox.NoInsert)
126 | completer = QCompleter(self._type_selector)
127 | completer.setCaseSensitivity(Qt.CaseSensitive)
128 | completer.setModel(self._type_selector.model())
129 | self._type_selector.setCompleter(completer)
130 | self._type_selector.on_commit = self._do_start
131 | self._type_selector.setFont(get_monospace_font())
132 | self._type_selector.setSizeAdjustPolicy(QComboBox.AdjustToContents)
133 | self._type_selector.setFocus(Qt.OtherFocusReason)
134 |
135 | self._active_filter = None
136 | self._filter_bar = FilterBar(self)
137 | self._filter_bar.on_filter = self._install_filter
138 |
139 | self._start_stop_button = make_icon_button('fa6s.video', 'Begin subscription', self, checkable=True,
140 | on_clicked=self._toggle_start_stop)
141 | self._pause_button = make_icon_button('fa6s.pause', 'Pause updates, non-displayed messages will be queued in memory',
142 | self, checkable=True)
143 | self._clear_button = make_icon_button('fa6s.trash', 'Clear output and reset stat counters', self,
144 | on_clicked=self._do_clear)
145 |
146 | self._show_all_message_types = make_icon_button('fa6s.puzzle-piece',
147 | 'Show all known message types, not only those that are '
148 | 'currently being exchanged over the bus',
149 | self, checkable=True, on_clicked=self._update_data_type_list)
150 |
151 | layout = QVBoxLayout(self)
152 |
153 | controls_layout = QHBoxLayout(self)
154 | controls_layout.addWidget(self._start_stop_button)
155 | controls_layout.addWidget(self._pause_button)
156 | controls_layout.addWidget(self._clear_button)
157 | controls_layout.addWidget(self._filter_bar.add_filter_button)
158 | controls_layout.addWidget(self._show_all_message_types)
159 | controls_layout.addWidget(self._type_selector, 1)
160 | controls_layout.addWidget(self._num_rows_spinbox)
161 |
162 | layout.addLayout(controls_layout)
163 | layout.addWidget(self._filter_bar)
164 | layout.addWidget(self._log_viewer, 1)
165 |
166 | stats_layout = QHBoxLayout(self)
167 | stats_layout.addWidget(self._num_messages_total_label)
168 | stats_layout.addWidget(self._num_messages_past_filter_label)
169 | stats_layout.addWidget(self._msgs_per_sec_label)
170 | layout.addLayout(stats_layout)
171 |
172 | self.setLayout(layout)
173 |
174 | # Initial updates
175 | self._update_data_type_list()
176 |
177 | def _install_filter(self, f):
178 | self._active_filter = f
179 |
180 | def _apply_filter(self, yaml_message):
181 | """This function will throw if the filter expression is malformed!"""
182 | if self._active_filter is None:
183 | return True
184 | return self._active_filter.match(yaml_message)
185 |
186 | def _on_message(self, e):
187 | # Global statistics
188 | self._num_messages_total += 1
189 |
190 | # Rendering and filtering
191 | try:
192 | text = dronecan.to_yaml(e)
193 | if not self._apply_filter(text):
194 | return
195 | except Exception as ex:
196 | self._num_errors += 1
197 | text = '!!! [%d] MESSAGE PROCESSING FAILED: %s' % (self._num_errors, ex)
198 | else:
199 | self._num_messages_past_filter += 1
200 | self._msgs_per_sec_estimator.register_event(e.transfer.ts_monotonic)
201 |
202 | # Sending the text for later rendering
203 | try:
204 | self._message_queue.put_nowait(text)
205 | except queue.Full:
206 | pass
207 |
208 | def _toggle_start_stop(self):
209 | try:
210 | if self._subscriber_handle is None:
211 | self._do_start()
212 | else:
213 | self._do_stop()
214 | finally:
215 | self._start_stop_button.setChecked(self._subscriber_handle is not None)
216 |
217 | def _do_stop(self):
218 | if self._subscriber_handle is not None:
219 | self._subscriber_handle.remove()
220 | self._subscriber_handle = None
221 |
222 | self._pause_button.setChecked(False)
223 | self.setWindowTitle(self.WINDOW_NAME_PREFIX)
224 |
225 | def _do_start(self):
226 | self._do_stop()
227 | self._do_clear()
228 |
229 | try:
230 | selected_type = self._type_selector.currentText().strip()
231 | if not selected_type:
232 | return
233 | data_type = dronecan.TYPENAMES[selected_type]
234 | except Exception as ex:
235 | show_error('Subscription error', 'Could not load requested data type', ex, self)
236 | return
237 |
238 | try:
239 | self._subscriber_handle = self._node.add_handler(data_type, self._on_message)
240 | except Exception as ex:
241 | show_error('Subscription error', 'Could not create requested subscription', ex, self)
242 | return
243 |
244 | self.setWindowTitle('%s [%s]' % (self.WINDOW_NAME_PREFIX, selected_type))
245 | self._start_stop_button.setChecked(True)
246 |
247 | def _do_redraw(self):
248 | self._num_messages_total_label.set(self._num_messages_total)
249 | self._num_messages_past_filter_label.set(self._num_messages_past_filter)
250 |
251 | estimated_rate = self._msgs_per_sec_estimator.get_rate_with_timestamp()
252 | self._msgs_per_sec_label.set('N/A' if estimated_rate is None else ('%.0f' % estimated_rate[0]))
253 |
254 | if self._pause_button.isChecked():
255 | return
256 |
257 | self._log_viewer.setUpdatesEnabled(False)
258 | while True:
259 | try:
260 | text = self._message_queue.get_nowait()
261 | except queue.Empty:
262 | break
263 | else:
264 | self._log_viewer.appendPlainText(text + '\n')
265 |
266 | self._log_viewer.setUpdatesEnabled(True)
267 |
268 | def _update_data_type_list(self):
269 | logger.info('Updating data type list')
270 | if self._show_all_message_types.isChecked():
271 | items = self._active_data_type_detector.get_names_of_all_message_types_with_data_type_id()
272 | else:
273 | items = self._active_data_type_detector.get_names_of_active_messages()
274 | self._type_selector.clear()
275 | self._type_selector.addItems(items)
276 |
277 | def _do_clear(self):
278 | self._num_messages_total = 0
279 | self._num_messages_past_filter = 0
280 | self._do_redraw()
281 | self._log_viewer.clear()
282 |
283 | def closeEvent(self, qcloseevent):
284 | try:
285 | self._subscriber_handle.close()
286 | except Exception:
287 | pass
288 | super(SubscriberWindow, self).closeEvent(qcloseevent)
289 |
290 | @staticmethod
291 | def spawn(parent, node, active_data_type_detector):
292 | SubscriberWindow(parent, node, active_data_type_detector).show()
293 |
--------------------------------------------------------------------------------
/dronecan_gui_tool/widgets/table_display.py:
--------------------------------------------------------------------------------
1 | '''
2 | a table display widget that takes a key to detemine table row
3 | '''
4 | import dronecan
5 | from PyQt5.QtWidgets import QTableWidget, QTableWidgetItem
6 | from PyQt5.QtCore import Qt, QTimer
7 | import time
8 |
9 |
10 | class TableDisplay(QTableWidget):
11 | '''table viewer'''
12 | def __init__(self, headers, expire_time=2.0):
13 | QTableWidget.__init__(self, 0, len(headers))
14 | self.headers = headers
15 | self.row_keys = []
16 | self.timestamps = {}
17 | self.setHorizontalHeaderLabels(self.headers)
18 | self.resizeColumnsToContents()
19 | self.resizeRowsToContents()
20 | self.expire_time = expire_time
21 | self.show()
22 | self.data = {}
23 | if self.expire_time is not None:
24 | QTimer.singleShot(int(expire_time*500), self.check_expired)
25 |
26 | def update(self, row_key, row):
27 | '''update a row'''
28 | if not row_key in self.row_keys:
29 | # new row
30 | self.timestamps[row_key] = time.time()
31 | self.insertRow(len(self.row_keys))
32 | self.row_keys.append(row_key)
33 |
34 | self.timestamps[row_key] = time.time()
35 | row_idx = self.row_keys.index(row_key)
36 | self.data[row_key] = row
37 | for i in range(len(row)):
38 | self.setItem(row_idx, i, QTableWidgetItem(str(row[i])))
39 |
40 | self.resizeColumnsToContents()
41 | self.resizeRowsToContents()
42 | self.show()
43 |
44 | def get(self, row_key):
45 | '''get current data for a row'''
46 | return self.data.get(row_key,None)
47 |
48 | def get_selected(self):
49 | '''get the selected row key'''
50 | row = self.currentRow()
51 | if row is None:
52 | return None
53 | return self.row_keys[row]
54 |
55 | def remove_row(self, row_key):
56 | '''remove a row'''
57 | if not row_key in self.row_keys:
58 | return
59 | row_idx = self.row_keys.index(row_key)
60 | if row_idx != -1:
61 | self.row_keys.pop(row_idx)
62 | self.removeRow(row_idx)
63 |
64 | def check_expired(self):
65 | '''check for expired rows'''
66 | keys = list(self.timestamps.keys())
67 | now = time.time()
68 | for key in keys:
69 | if now - self.timestamps[key] >= self.expire_time:
70 | # remove old rows
71 | self.timestamps.pop(key)
72 | self.remove_row(key)
73 | QTimer.singleShot(int(self.expire_time*500), self.check_expired)
74 |
75 |
76 |
--------------------------------------------------------------------------------
/icons/logo.ico:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/dronecan/gui_tool/bbab5bdb80f46aeae720259850d8cace1d27586f/icons/logo.ico
--------------------------------------------------------------------------------
/pip_sizes.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | import os
4 | import pkg_resources
5 |
6 | def calc_container(path):
7 | total_size = 0
8 | for dirpath, dirnames, filenames in os.walk(path):
9 | for f in filenames:
10 | fp = os.path.join(dirpath, f)
11 | total_size += os.path.getsize(fp)
12 | return total_size
13 |
14 |
15 |
16 | dists = [d for d in pkg_resources.working_set]
17 |
18 | data = {}
19 | data2 = []
20 | data3 = {}
21 |
22 | for dist in dists:
23 | try:
24 | path = os.path.join(dist.location, dist.project_name)
25 | size = calc_container(path)
26 | if size/1000 > 1.0:
27 | #print (f"{dist}: {size/1000} KB")
28 | data[size] = f"{dist}: {size/1000} KB"
29 | a = f"{dist}"
30 | data2.append(a.split()[0])# first word
31 | data3[a.split()[0]] = f"{dist}: {size/1000} KB"
32 | except OSError:
33 | '{} no longer exists'.format(dist.project_name)
34 |
35 | sorted_dict = dict(sorted(data.items()))
36 | sorted_dict2 = sorted(data2)
37 |
38 | print("--------alpha-sorted-package-names-----------------")
39 | for i in sorted_dict2:
40 | print(data3[i])
41 |
42 | #exit()
43 | print("\n--------size-sorted-package-info-----------------")
44 | total = 0
45 | for i in sorted_dict:
46 | print(i,sorted_dict[i])
47 | total += i
48 | print("Total %.2f MByte" % (total * 1.0e-6))
49 |
50 |
51 |
--------------------------------------------------------------------------------
/pyproject.toml:
--------------------------------------------------------------------------------
1 | # modern build tools use this file: https://packaging.python.org/en/latest/tutorials/packaging-projects/
2 | # you need to drop setup_requires from setup.py as well.
3 | # https://peps.python.org/pep-0518/#rationale
4 | [build-system]
5 | requires = ["setuptools>=42",'setuptools_git>=1.0']
6 | build-backend = "setuptools.build_meta"
7 |
--------------------------------------------------------------------------------
/remove_build_outputs.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | sudo rm -rf build dronecan_gui_tool.* dist* *-*.egg
3 |
--------------------------------------------------------------------------------
/screenshot.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/dronecan/gui_tool/bbab5bdb80f46aeae720259850d8cace1d27586f/screenshot.png
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 | #
3 | # Copyright (C) 2016 UAVCAN Development Team
4 | #
5 | # This software is distributed under the terms of the MIT License.
6 | #
7 | # Author: Pavel Kirienko
8 | #
9 |
10 | import os
11 | import sys
12 | import shutil
13 | import pkg_resources
14 | import glob
15 | from setuptools import setup, find_packages
16 | from setuptools.archive_util import unpack_archive
17 |
18 | PACKAGE_NAME = 'dronecan_gui_tool'
19 | HUMAN_FRIENDLY_NAME = 'DroneCAN GUI Tool'
20 |
21 | SOURCE_DIR = os.path.abspath(os.path.dirname(__file__))
22 |
23 | # unique code so the package can be upgraded as an MSI
24 | upgrade_code = '{D5CD6E19-2545-32C7-A62A-4595B28BCDC3}'
25 |
26 | sys.path.append(os.path.join(SOURCE_DIR, PACKAGE_NAME))
27 | from version import __version__
28 |
29 | assert sys.version_info[0] == 3, 'Python 3 is required'
30 |
31 | with open("README.md", "r", encoding = "utf-8") as fh:
32 | long_description = fh.read()
33 |
34 | #
35 | # Setup args common for all targets
36 | #
37 | args = dict(
38 | name=PACKAGE_NAME,
39 | version='.'.join(map(str, __version__)),
40 | packages=find_packages(),
41 | install_requires=[
42 | 'setuptools>=18.5',
43 | 'dronecan>=1.0.25',
44 | 'pyserial>=3.0',
45 | 'pymavlink>=2.4.26',
46 | 'qtawesome>=1.4.0',
47 | 'qtconsole>=4.2.0',
48 | 'pyyaml>=5.1',
49 | 'easywebdav>=1.2',
50 | 'pymonocypher',
51 | 'numpy',
52 | 'pyqt5',
53 | 'traitlets',
54 | 'jupyter-client',
55 | 'ipykernel',
56 | 'pygments',
57 | 'qtpy',
58 | 'pyqtgraph',
59 | 'qtwidgets',
60 | 'intelhex'
61 | ],
62 | # We can't use "scripts" here, because generated shims don't work with multiprocessing pickler.
63 | entry_points={
64 | 'gui_scripts': [
65 | '{0}={0}.main:main'.format(PACKAGE_NAME),
66 | ]
67 | },
68 | include_package_data=True,
69 |
70 | # Meta fields, they have no technical meaning
71 | description='DroneCAN Bus Management and Diagnostics App',
72 | long_description = long_description,
73 | long_description_content_type = "text/markdown",
74 | author='DroneCAN Development Team',
75 | author_email='dronecan.devel@gmail.com',
76 | url='http://dronecan.org',
77 | license='MIT',
78 | classifiers=[
79 | 'Development Status :: 5 - Production/Stable',
80 | 'Intended Audience :: End Users/Desktop',
81 | 'Intended Audience :: Developers',
82 | 'Topic :: Scientific/Engineering :: Human Machine Interfaces',
83 | 'Topic :: Scientific/Engineering :: Visualization',
84 | 'License :: OSI Approved :: MIT License',
85 | 'Programming Language :: Python :: 3',
86 | 'Environment :: X11 Applications',
87 | 'Environment :: Win32 (MS Windows)',
88 | 'Environment :: MacOS X',
89 | ],
90 | package_data={'DroneCAN_GUI_Tool': [ 'icons/*.png', 'icons/*.ico']}
91 | )
92 |
93 | if sys.platform.startswith('linux') or sys.platform.startswith('darwin'):
94 | # Delegating the desktop integration work to 'install_freedesktop'
95 | args.setdefault('setup_requires', []).append('install_freedesktop')
96 |
97 | args['desktop_entries'] = {
98 | PACKAGE_NAME: {
99 | 'Name': HUMAN_FRIENDLY_NAME,
100 | 'GenericName': args['description'],
101 | 'Comment': args['description'],
102 | 'Categories': 'Development;Utility;',
103 | }
104 | }
105 |
106 | # Manually invoking the freedesktop extension - this should work even if we're getting installed via PIP
107 | sys.argv.append('install_desktop')
108 |
109 |
110 | #
111 | # Windows-specific options and hacks
112 | #
113 | if os.name == 'nt':
114 | args.setdefault('install_requires', []).append('cx_Freeze ~= 6.1')
115 |
116 | if ('bdist_msi' in sys.argv) or ('build_exe' in sys.argv):
117 | import cx_Freeze
118 |
119 | # cx_Freeze can't handle 3rd-party packages packed in .egg files, so we have to extract them for it
120 | dependency_eggs_to_unpack = [
121 | 'dronecan',
122 | 'qtpy',
123 | 'qtconsole',
124 | 'easywebdav',
125 | ]
126 | unpacked_eggs_dir = os.path.join('build', 'hatched_eggs')
127 | sys.path.insert(0, unpacked_eggs_dir)
128 | try:
129 | shutil.rmtree(unpacked_eggs_dir)
130 | except Exception:
131 | pass
132 | for dep in dependency_eggs_to_unpack:
133 | for egg in pkg_resources.require(dep):
134 | if not os.path.isdir(egg.location):
135 | unpack_archive(egg.location, unpacked_eggs_dir)
136 |
137 | import qtawesome
138 | import qtconsole
139 | import PyQt5
140 | import zmq
141 | import pygments
142 | import IPython
143 | import ipykernel
144 | import jupyter_client
145 | import traitlets
146 | import numpy
147 |
148 | # Oh, Windows, never change.
149 | missing_dlls = glob.glob(os.path.join(os.path.dirname(numpy.core.__file__), '*.dll'))
150 | print('Missing DLL:', missing_dlls)
151 |
152 | # My reverence for you, I hope, will help control my inborn instability; we are accustomed to a zigzag way of life.
153 | args['options'] = {
154 | 'build_exe': {
155 | 'packages': [
156 | 'pkg_resources',
157 | 'zmq',
158 | 'pygments',
159 | 'jupyter_client',
160 | ],
161 | 'include_msvcr': True,
162 | 'include_files': [
163 | PACKAGE_NAME,
164 | # These packages don't work properly when packed in .zip, so here we have another bunch of ugly hacks
165 | os.path.join(unpacked_eggs_dir, os.path.dirname(PyQt5.__file__)),
166 | os.path.join(unpacked_eggs_dir, os.path.dirname(qtawesome.__file__)),
167 | os.path.join(unpacked_eggs_dir, os.path.dirname(qtconsole.__file__)),
168 | os.path.join(unpacked_eggs_dir, os.path.dirname(zmq.__file__)),
169 | os.path.join(unpacked_eggs_dir, os.path.dirname(pygments.__file__)),
170 | os.path.join(unpacked_eggs_dir, os.path.dirname(IPython.__file__)),
171 | os.path.join(unpacked_eggs_dir, os.path.dirname(ipykernel.__file__)),
172 | os.path.join(unpacked_eggs_dir, os.path.dirname(jupyter_client.__file__)),
173 | os.path.join(unpacked_eggs_dir, os.path.dirname(traitlets.__file__)),
174 | os.path.join(unpacked_eggs_dir, os.path.dirname(numpy.__file__)),
175 | ] + missing_dlls,
176 | },
177 | 'bdist_msi': {
178 | 'upgrade_code' : upgrade_code,
179 | 'initial_target_dir': '[ProgramFilesFolder]\\DroneCAN\\' + HUMAN_FRIENDLY_NAME,
180 | },
181 | }
182 | args['executables'] = [
183 | cx_Freeze.Executable(os.path.join('bin', PACKAGE_NAME),
184 | base='Win32GUI',
185 | icon='icons/logo.ico',
186 | shortcut_name=HUMAN_FRIENDLY_NAME,
187 | shortcut_dir='ProgramMenuFolder'),
188 | ]
189 | # Dispatching to cx_Freeze only if MSI build was requested explicitly. Otherwise continue with regular setup.
190 | # This is done in order to be able to install dependencies with regular setuptools.
191 | def setup(*args, **kwargs):
192 | cx_Freeze.setup(*args, **kwargs)
193 |
194 | setup(**args)
195 |
--------------------------------------------------------------------------------
/winbuild.bat:
--------------------------------------------------------------------------------
1 | @echo on
2 |
3 | rem - this is a sample build script for building gui_tool MSI file under windows, it assumes the following:
4 | rem - you already have a python.org python installed (at least 3.10) tested on 3.10.2
5 | rem - you have a git checkout of [the correct] gui_tool [release] here
6 |
7 | rem - how to use:
8 | rem - step 1 - edit the script to change the PATH below to include your python 3.10 install directory
9 | rem - step 2 - open a command prompt
10 | rem - step 3 - run winbuild.bat in the gui_tool directory
11 |
12 | rem NOTE: you need visual studio installed, with the C++ build tools
13 |
14 | SET PATH=f:\WinPython;%PATH%
15 |
16 | python --version
17 |
18 | python -m pip install -U cx_Freeze
19 | python -m pip install -U pymavlink
20 | python -m pip install -U pywin32
21 | python -m pip install -U python-can
22 | python -m pip install -U .
23 |
24 | rem show pip sizes for debug
25 | python pip_sizes.py
26 |
27 | rem make the .msi
28 | python setup.py install
29 | python setup.py bdist_msi
30 |
31 | rem find the binary in 'dist' folder
32 | dir dist
33 |
--------------------------------------------------------------------------------