Merge branch 'release_7.0.0' of https://github.com/iNavFlight/inav-configurator into FW-Autoland
|
@ -175,13 +175,13 @@ https://hub.docker.com/r/yagajs/mapproxy/ Docker image (untested)
|
||||||
base: GLOBAL_MERCATOR
|
base: GLOBAL_MERCATOR
|
||||||
origin: ul
|
origin: ul
|
||||||
```
|
```
|
||||||
1. You can use any map provider that is compatible with MapProxy, and once you zoom in on the region you will be flying in, the map tiles will be cached for offline use. You can test this by disabling your internet connection and browsing the demo url in a browser
|
1. You can use any map provider that is compatible with MapProxy, and once you zoom in on the region you will be flying in, the map tiles will be cached for offline use. You can test this by disabling your internet connection and browsing the demo URL in a browser
|
||||||
|
|
||||||
https://wiki.openstreetmap.org/wiki/WMS#OSM_WMS_Servers OpenStreetMap WSM servers
|
https://wiki.openstreetmap.org/wiki/WMS#OSM_WMS_Servers OpenStreetMap WSM servers
|
||||||
|
|
||||||
https://lpdaac.usgs.gov/data_access/web_map_services_wms # USGS currently has 400+ WMS layers
|
https://lpdaac.usgs.gov/data_access/web_map_services_wms # USGS currently has 400+ WMS layers
|
||||||
|
|
||||||
* You can use QGIS to browse different provieders and pick the maps you like for your iNav layers
|
* You can use QGIS to browse different providers and pick the maps you like for your iNav layers
|
||||||
https://qgis.org/en/site/
|
https://qgis.org/en/site/
|
||||||
|
|
||||||
* There are many government and public wms providers available in different regions worldwide
|
* There are many government and public WMS providers available in different regions worldwide
|
||||||
|
|
119
README.md
|
@ -1,89 +1,121 @@
|
||||||
# INAV Configurator
|
# INAV Configurator
|
||||||
|
|
||||||
INAV Configurator is a crossplatform configuration tool for the [INAV](https://github.com/iNavFlight/inav) flight control system.
|
INAV Configurator is a cross-platform configuration tool for the [INAV](https://github.com/iNavFlight/inav) flight control system.
|
||||||
|
|
||||||
It runs as an app within Google Chrome and allows you to configure the INAV software running on any supported INAV target.
|
It runs as an app within Google Chrome and allows you to configure the INAV software running on any supported INAV target.
|
||||||
|
|
||||||
Various types of aircraft are supported by the tool and by INAV, e.g. quadcopters, hexacopters, octocopters and fixed-wing aircraft.
|
Various types of aircraft are supported by the tool and by INAV, e.g. quadcopters, hexacopters, octocopters, and fixed-wing aircraft.
|
||||||
|
|
||||||
# Support
|
# Support
|
||||||
|
|
||||||
INAV Configurator comes `as is`, without any warranty and support from authors. If you found a bug, please create an issue on [GitHub](https://github.com/iNavFlight/inav-configurator/issues).
|
INAV Configurator comes `as is`, without any warranty and support from the authors. If you find a bug, please create an issue on [GitHub](https://github.com/iNavFlight/inav-configurator/issues).
|
||||||
|
|
||||||
GitHub issue tracker is reserved for bugs and other technical problems. If you do not know how to setup
|
The GitHub issue tracker is reserved for bugs and other technical problems. If you do not know how to set up
|
||||||
everything, hardware is not working or have any other _support_ problem, please consult:
|
everything, the hardware is not working, or you have any other _support_ problem, please consult:
|
||||||
|
|
||||||
* [INAV Discord Server](https://discord.gg/peg2hhbYwN)
|
* [INAV Discord Server](https://discord.gg/peg2hhbYwN)
|
||||||
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
|
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
|
||||||
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
|
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
|
||||||
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
||||||
|
|
||||||
## INAV Configurator start minimized, what should I do?
|
## INAV Configurator starts minimized, what should I do?
|
||||||
|
|
||||||
You have to remove `C:\Users%Your_UserNname%\AppData\Local\inav-configurator` folder and all its content.
|
You have to remove the `C:\Users%Your_UserName%\AppData\Local\inav-configurator` folder and all its content.
|
||||||
|
|
||||||
[https://www.youtube.com/watch?v=XMoULyiFDp4](https://www.youtube.com/watch?v=XMoULyiFDp4)
|
[https://www.youtube.com/watch?v=XMoULyiFDp4](https://www.youtube.com/watch?v=XMoULyiFDp4)
|
||||||
|
|
||||||
Alternatively, on Windows with PowerShell you can use `post_install_cleanup.ps1` script that will do the cleaning. (thank you James Cherrill)
|
Alternatively, on Windows with PowerShell, you can use the `post_install_cleanup.ps1` script that will do the cleaning. (thank you, James Cherrill)
|
||||||
|
|
||||||
## Installation
|
## Installation
|
||||||
|
|
||||||
Depending on target operating system, _INAV Configurator_ is distributed as _standalone_ application or Chrome App.
|
Depending on the target operating system, _INAV Configurator_ is distributed as a _standalone_ application or Chrome App.
|
||||||
|
|
||||||
### Windows
|
### Windows
|
||||||
|
|
||||||
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
||||||
1. Download Configurator for Windows platform (win32 or win64 is present)
|
1. Download Configurator for Windows platform (win32 or win64 is present)
|
||||||
1. Extract ZIP archive
|
1. Extract ZIP archive
|
||||||
1. Run INAV Configurator app from unpacked folder
|
1. Run the INAV Configurator app from the unpacked folder
|
||||||
1. Configurator is not signed, so you have to allow Windows to run untrusted application. There might be a monit for it during first run
|
1. Configurator is not signed, so you have to allow Windows to run untrusted applications. There might be a monit for it during the first run
|
||||||
|
|
||||||
### Linux
|
### Linux
|
||||||
|
|
||||||
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
||||||
1. Download Configurator for Linux platform (linux32 and linux64 are present)
|
2. Download Configurator for Linux platform (linux32 and linux64 are present)
|
||||||
1. Extract tar.gz archive
|
* **.rpm** is the Fedora installation file. Just download and install using `sudo dnf localinstall /path/to/INAV-Configurator_linux64-x.y.z-x86_64.rpm` or open it with a package manager (e.g. via Files)
|
||||||
1. Make the following files executable:
|
* **.deb** is the Debian/Ubuntu installation file. Just download and install using `sudo apt install /path/to/INAV-Configurator_linux64_x.y.z.deb` or open it with a package manager (e.g. via the File Manager)
|
||||||
* inav-configurator `chmod +x inav-configurator`
|
* **.tar.gz** is a universal archive. Download and continue with these instructions to install
|
||||||
* (5.0.0+) chrome_crashpad_handler `chmod +x chrome_crashpad_handler`
|
3. Change to the directory containing the downloaded **tar.gz** file
|
||||||
1. Run INAV Configurator app from unpacked folder
|
4. download [this](https://raw.githubusercontent.com/iNavFlight/inav-configurator/master/assets/linux/inav-configurator.desktop) file to the same directory. Its filename should be `inav-configurator.desktop`.
|
||||||
|
5. Extract **tar.gz** archive
|
||||||
|
```
|
||||||
|
tar -C /tmp/ -xf INAV-Configurator_linuxNN_x.y.z.tar.gz
|
||||||
|
```
|
||||||
|
**NN** is the bits of your OS. **x.y.z** is the INAV Configurator version number.
|
||||||
|
|
||||||
On some Linux distros, you may be missing `libatomic`, a `NW.JS` (specially `libnode.so`) dependency. If so, please install `libatomic` using your distro's package manager, e.g:
|
6. If this is the first time installing INAV Configurator, create a home for its files
|
||||||
|
```
|
||||||
|
sudo mkdir /opt/inav
|
||||||
|
sudo chown $USER /opt/inav
|
||||||
|
```
|
||||||
|
7. Move the temporary files into their home
|
||||||
|
```
|
||||||
|
mv /tmp/INAV\ Configurator /opt/inav/inav-configurator
|
||||||
|
```
|
||||||
|
8. Update the application icon.
|
||||||
|
```
|
||||||
|
sudo mkdir /opt/inav/inav-configurator/icon
|
||||||
|
sudo cp /opt/inav/inav-configurator/images/inav_icon_128.png /opt/inav/inav-configurator/icon
|
||||||
|
```
|
||||||
|
9. As a one-off, move the desktop file into the applications directory
|
||||||
|
```
|
||||||
|
sudo mv inav-configurator.desktop /usr/share/applications/
|
||||||
|
```
|
||||||
|
10. Make the following files executable:
|
||||||
|
* inav-configurator `chmod +x /opt/inav/inav-configurator/inav-configurator`
|
||||||
|
* (5.0.0+) chrome_crashpad_handler `chmod +x /opt/inav/inav-configurator/chrome_crashpad_handler`
|
||||||
|
11. Run the INAV Configurator app from the unpacked folder `/opt/inav/inav-configurator/inav-configurator`
|
||||||
|
|
||||||
|
#### Notes
|
||||||
|
|
||||||
|
On some Linux distros, you may be missing `libatomic` and/or `NW.JS` (especially `libnode.so`) dependencies. If so, please install `libatomic` using your distro's package manager, e.g:
|
||||||
|
|
||||||
* Arch Linux: `sudo pacman -S --needed libatomic_ops`
|
* Arch Linux: `sudo pacman -S --needed libatomic_ops`
|
||||||
* Debian / Ubuntu: `sudo apt install libatomic1`
|
* Debian / Ubuntu: `sudo apt install libatomic1`
|
||||||
* Fedora: `sudo dnf install libatomic`
|
* Fedora: `sudo dnf install libatomic`
|
||||||
|
|
||||||
|
1. Don't forget to add your user to the dialout group "sudo usermod -aG dialout YOUR_USERNAME" for serial access
|
||||||
|
2. If you have 3D model animation problems, enable "Override software rendering list" in Chrome flags chrome://flags/#ignore-gpu-blacklist
|
||||||
|
|
||||||
### Mac
|
### Mac
|
||||||
|
|
||||||
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
||||||
1. Download Configurator for Mac platform
|
1. Download Configurator for the Mac platform
|
||||||
1. Extract ZIP archive
|
1. Extract ZIP archive
|
||||||
1. Run INAV Configurator
|
1. Run INAV Configurator
|
||||||
1. Configurator is not signed, so you have to allow Mac to run untrusted application. There might be a monit for it during first run
|
|
||||||
|
|
||||||
## Building and running INAV Configurator locally (for development or Linux users)
|
## Building and running INAV Configurator locally (for development)
|
||||||
|
|
||||||
For local development, **node.js** build system is used.
|
For local development, the **node.js** build system is used.
|
||||||
|
|
||||||
1. Install node.js
|
1. Install node.js
|
||||||
1. From project folder run `npm install`
|
1. From the project folder run `npm install`
|
||||||
1. To build the JS and CSS files and start the configurator:
|
1. To build the JS and CSS files and start the configurator:
|
||||||
- With NW.js: Run `npm start`.
|
- With NW.js: Run `npm start`.
|
||||||
- With Chrome: Run `npm run gulp`. Then open `chrome://extensions`, enable
|
- With Chrome: Run `npm run gulp`. Then open `chrome://extensions`, enable
|
||||||
the `Developer mode`, click on the `Load unpacked extension...` button and select the `inav-configurator` directory.
|
the `Developer mode`, click on the `Load unpacked extension...` button, and select the `inav-configurator` directory.
|
||||||
|
|
||||||
Other tasks are also defined in `gulpfile.js`. To run a task, use `node ./node_modules/gulp/bin/gulp.js task-name`. Available ones are:
|
Other tasks are also defined in `gulpfile.js`. To run a task, use `node ./node_modules/gulp/bin/gulp.js task-name`. Available ones are:
|
||||||
|
|
||||||
- **build**: Generate JS and CSS output files used by the configurator from their sources. It must be run whenever changes are made to any `.js` or `.css` files in order to have those changes appear
|
- **build**: Generate JS and CSS output files used by the configurator from their sources. It must be run whenever changes are made to any `.js` or `.css` files in order to have those changes appear
|
||||||
in the configurator. If new files are added, they must be included in `gulpfile.js`. See the comments at the top of `gulpfile.js` to learn how to do so. See also the `watch` task.
|
in the configurator. If new files are added, they must be included in `gulpfile.js`. See the comments at the top of `gulpfile.js` to learn how to do so. See also the `watch` task.
|
||||||
- **watch**: Watch JS and CSS sources for changes and run the `build` task whenever they're edited.
|
- **watch**: Watch JS and CSS sources for changes and run the `build` task whenever they're edited.
|
||||||
- **dist**: Create a distribution of the app (valid for packaging both as a Chrome app or a NW.js app)
|
- **dist**: Create a distribution of the app (valid for packaging both as a Chrome app or NW.js app)
|
||||||
in the `./dist/` directory.
|
in the `./dist/` directory.
|
||||||
- **release**: Create NW.js apps for each supported platform (win32, osx64 and linux64) in the `./apps`
|
- **release**: Create NW.js apps for each supported platform (win32, osx64 and linux64) in the `./apps`
|
||||||
directory. Running this task on macOS or Linux requires Wine, since it's needed to set the icon
|
directory. Running this task on macOS or Linux requires Wine since it's needed to set the icon
|
||||||
for the Windows app. If you don't have Wine installed you can create a release by running the **release-only-linux** task.
|
for the Windows app. If you don't have Wine installed, you can create a release by running the **release-only-Linux** task.
|
||||||
<br>`--installer` argument can be added to build installers for particular OS. NOTE: MacOS Installer can be built with MacOS only.
|
<br>`--installer` argument can be added to build installers for a particular OS. NOTE: MacOS Installer can be built with MacOS only.
|
||||||
|
|
||||||
To build a specific release, use the command `release --platform="win64"` for example.
|
To build a specific release, use the command `release --platform="win64"` for example.
|
||||||
|
|
||||||
|
@ -95,17 +127,17 @@ To be able to open Inspector, you will need SDK flavours of NW.js
|
||||||
|
|
||||||
## Different map providers
|
## Different map providers
|
||||||
|
|
||||||
INAV Configurator 2.1 allows to choose between OpenStreetMap, Bing Maps (Aerial View), and MapProxy map providers.
|
INAV Configurator 2.1 allows you to choose between OpenStreetMap, Bing Maps (Aerial View), and MapProxy map providers.
|
||||||
INAV Configurator is shipped **WITHOUT** API key for Bing Maps. That means: every user who wants to use Bing Maps has to create own account, agree to all _Terms and Conditions_ required by Bing Maps and configure INAV Configuerator by himself.
|
INAV Configurator is shipped **WITHOUT** API key for Bing Maps. That means: every user who wants to use Bing Maps has to create their own account, agree to all _Terms and Conditions_ required by Bing Maps, and configure INAV Configurator by himself.
|
||||||
|
|
||||||
### How to choose Map provider
|
### How to choose a Map provider
|
||||||
|
|
||||||
1. Click **Settings** icon in the top-right corner of INAV Configurator
|
1. Click **Settings** icon in the top-right corner of INAV Configurator
|
||||||
1. Choose provider: OpenStreetMap, Bing, or MapProxy
|
1. Choose a provider: OpenStreetMap, Bing, or MapProxy
|
||||||
1. In the case of Bing Maps, you have to provide your own, personal, generated by you, Bing Maps API key
|
1. In the case of Bing Maps, you have to provide your own, personal, generated by you, Bing Maps API key
|
||||||
1. For MapProxy, you need to provide a server URL and layer name to be used
|
1. For MapProxy, you need to provide a server URL and layer name to be used
|
||||||
|
|
||||||
### How to get Bing Maps API key
|
### How to get the Bing Maps API key
|
||||||
|
|
||||||
1. Go to the Bing Maps Dev Center at [https://www.bingmapsportal.com/](https://www.bingmapsportal.com/).
|
1. Go to the Bing Maps Dev Center at [https://www.bingmapsportal.com/](https://www.bingmapsportal.com/).
|
||||||
* If you have a Bing Maps account, sign in with the Microsoft account that you used to create the account or create a new one. For new accounts, follow the instructions in [Creating a Bing Maps Account](https://msdn.microsoft.com/library/gg650598.aspx).
|
* If you have a Bing Maps account, sign in with the Microsoft account that you used to create the account or create a new one. For new accounts, follow the instructions in [Creating a Bing Maps Account](https://msdn.microsoft.com/library/gg650598.aspx).
|
||||||
|
@ -113,22 +145,22 @@ INAV Configurator is shipped **WITHOUT** API key for Bing Maps. That means: ever
|
||||||
1. Select the option to create a new key.
|
1. Select the option to create a new key.
|
||||||
1. Provide the following information to create a key:
|
1. Provide the following information to create a key:
|
||||||
1. Application name: Required. The name of the application.
|
1. Application name: Required. The name of the application.
|
||||||
1. Application URL: The URL of the application. This is an optional field which is useful in helping you remember the purpose of that key in the future.
|
1. Application URL: The URL of the application. This is an optional field that is useful in helping you remember the purpose of that key in the future.
|
||||||
1. Key type: Required. Select the key type that you want to create. You can find descriptions of key and application types here.
|
1. Key type: Required. Select the key type that you want to create. You can find descriptions of key and application types here.
|
||||||
1. Application type: Required. Select the application type that best represents the application that will use this key. You can find descriptions of key and application types [here](https://www.microsoft.com/maps/create-a-bing-maps-key.aspx).
|
1. Application type: Required. Select the application type that best represents the application that will use this key. You can find descriptions of key and application types [here](https://www.microsoft.com/maps/create-a-bing-maps-key.aspx).
|
||||||
1. Click the **Create** button. The new key displays in the list of available keys. Use this key to authenticate your Bing Maps application as described in the documentation for the Bing Maps API you are using.
|
1. Click the **Create** button. The new key is displayed in the list of available keys. Use this key to authenticate your Bing Maps application as described in the documentation for the Bing Maps API you are using.
|
||||||
|
|
||||||
### How to setup a MapProxy server for offline caching and mission planning
|
### How to set up a MapProxy server for offline caching and mission planning
|
||||||
1. Follow process described in [MAPPROXY.md](MAPPROXY.md)
|
1. Follow the process described in [MAPPROXY.md](MAPPROXY.md)
|
||||||
1. Test your MapProxy server in web browser, eg: http://192.168.145.20/inavmapproxy/
|
1. Test your MapProxy server in a web browser, eg: http://192.168.145.20/inavmapproxy/
|
||||||
1. Once you have a working MapProxy server choose MapProxy as your map provider
|
1. Once you have a working MapProxy server choose MapProxy as your map provider
|
||||||
1. Enter MapProxy service URL, eg: http://192.168.145.20/inavmapproxy/service?
|
1. Enter MapProxy service URL, eg: http://192.168.145.20/inavmapproxy/service?
|
||||||
1. Enter MapProxy service layer (inav_layer if configured from MAPPROXY.md)
|
1. Enter MapProxy service layer (inav_layer if configured from MAPPROXY.md)
|
||||||
1. Once completed, you can zoom in on area you will be flying in while connected to the internet in either GPS or Mission Control tab to save the cache for offline use
|
1. Once completed, you can zoom in on the area you will be flying in while connected to the internet in either the GPS or Mission Control tab to save the cache for offline use
|
||||||
|
|
||||||
## Font Customisation
|
## Font Customisation
|
||||||
|
|
||||||
INAV provides the font images so that custom fonts can be created for your personal preference. This is the case for both analogue and digital fonts. The resources can be found in the [osd](/resources/osd) folder. Within the **analogue** and **digital** subfolders, you will find information on compiling your own fonts. There is also an [INAV Character Map](/resources/osd/INAV%20Character%20Map.md) document. This contains previews of all the character images in the fonts, and the appropriate variable names within the firmware and Configurator. There are tools for compiling the [analogue](https://github.com/fiam/max7456tool) and [digital](https://github.com/MrD-RC/hdosd-font-tool) fonts. New font submissions via pull requests are welcome.
|
INAV provides the font images so that custom fonts can be created for your personal preference. This is the case for both analogue and digital fonts. The resources can be found in the [osd](/resources/osd) folder. Within the **analogue** and **digital** subfolders, you will find information on compiling your own fonts. There is also an [INAV Character Map](/resources/osd/INAV%20Character%20Map.md) document. This contains previews of all the character images in the fonts and the appropriate variable names within the firmware and Configurator. There are tools for compiling the [analogue](https://github.com/fiam/max7456tool) and [digital](https://github.com/MrD-RC/hdosd-font-tool) fonts. New font submissions via pull requests are welcome.
|
||||||
|
|
||||||
## Notes
|
## Notes
|
||||||
|
|
||||||
|
@ -136,18 +168,13 @@ INAV provides the font images so that custom fonts can be created for your perso
|
||||||
|
|
||||||
Make sure Settings -> System -> "User hardware acceleration when available" is checked to achieve the best performance
|
Make sure Settings -> System -> "User hardware acceleration when available" is checked to achieve the best performance
|
||||||
|
|
||||||
### Linux users
|
|
||||||
|
|
||||||
1. Dont forget to add your user into dialout group "sudo usermod -aG dialout YOUR_USERNAME" for serial access
|
|
||||||
2. If you have 3D model animation problems, enable "Override software rendering list" in Chrome flags chrome://flags/#ignore-gpu-blacklist
|
|
||||||
|
|
||||||
## Issue trackers
|
## Issue trackers
|
||||||
|
|
||||||
For INAV configurator issues raise them here
|
For INAV configurator issues raise them here
|
||||||
|
|
||||||
https://github.com/iNavFlight/inav-configurator/issues
|
https://github.com/iNavFlight/inav-configurator/issues
|
||||||
|
|
||||||
For INAV firmware issues raise them here
|
For INAV firmware issues, raise them here
|
||||||
|
|
||||||
https://github.com/iNavFlight/inav/issues
|
https://github.com/iNavFlight/inav/issues
|
||||||
|
|
||||||
|
|
|
@ -126,6 +126,7 @@ sources.js = [
|
||||||
'./js/serial_queue.js',
|
'./js/serial_queue.js',
|
||||||
'./js/msp_balanced_interval.js',
|
'./js/msp_balanced_interval.js',
|
||||||
'./tabs/advanced_tuning.js',
|
'./tabs/advanced_tuning.js',
|
||||||
|
'./tabs/ez_tune.js',
|
||||||
'./js/peripherals.js',
|
'./js/peripherals.js',
|
||||||
'./js/appUpdater.js',
|
'./js/appUpdater.js',
|
||||||
'./js/feature_framework.js',
|
'./js/feature_framework.js',
|
||||||
|
|
|
@ -5,7 +5,7 @@ var appUpdater = appUpdater || {};
|
||||||
appUpdater.checkRelease = function (currVersion) {
|
appUpdater.checkRelease = function (currVersion) {
|
||||||
var modalStart;
|
var modalStart;
|
||||||
$.get('https://api.github.com/repos/iNavFlight/inav-configurator/releases', function (releaseData) {
|
$.get('https://api.github.com/repos/iNavFlight/inav-configurator/releases', function (releaseData) {
|
||||||
GUI.log('Loaded release information from GitHub.');
|
GUI.log(chrome.i18n.getMessage('loadedReleaseInfo'));
|
||||||
//Git return sorted list, 0 - last release
|
//Git return sorted list, 0 - last release
|
||||||
|
|
||||||
let newVersion = releaseData[0].tag_name;
|
let newVersion = releaseData[0].tag_name;
|
||||||
|
@ -15,7 +15,7 @@ appUpdater.checkRelease = function (currVersion) {
|
||||||
GUI.log(newVersion, chrome.runtime.getManifest().version);
|
GUI.log(newVersion, chrome.runtime.getManifest().version);
|
||||||
GUI.log(currVersion);
|
GUI.log(currVersion);
|
||||||
|
|
||||||
GUI.log('New version available!');
|
GUI.log(chrome.i18n.getMessage('newVersionAvailable'));
|
||||||
modalStart = new jBox('Modal', {
|
modalStart = new jBox('Modal', {
|
||||||
width: 400,
|
width: 400,
|
||||||
height: 200,
|
height: 200,
|
||||||
|
|
|
@ -2,8 +2,8 @@
|
||||||
|
|
||||||
var CONFIGURATOR = {
|
var CONFIGURATOR = {
|
||||||
// all versions are specified and compared using semantic versioning http://semver.org/
|
// all versions are specified and compared using semantic versioning http://semver.org/
|
||||||
'minfirmwareVersionAccepted': '6.0.0',
|
'minfirmwareVersionAccepted': '7.0.0',
|
||||||
'maxFirmwareVersionAccepted': '7.0.0', // Condition is < (lt) so we accept all in 6.x branch
|
'maxFirmwareVersionAccepted': '8.0.0', // Condition is < (lt) so we accept all in 7.x branch
|
||||||
'connectionValid': false,
|
'connectionValid': false,
|
||||||
'connectionValidCliOnly': false,
|
'connectionValidCliOnly': false,
|
||||||
'cliActive': false,
|
'cliActive': false,
|
||||||
|
|
|
@ -823,12 +823,6 @@ helper.defaultsDialog = (function () {
|
||||||
value: 25
|
value: 25
|
||||||
},
|
},
|
||||||
],
|
],
|
||||||
"features": [
|
|
||||||
{
|
|
||||||
bit: 4, // Enable MOTOR_STOP
|
|
||||||
state: true
|
|
||||||
}
|
|
||||||
]
|
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"title": 'Airplane without a Tail (Wing, Delta, etc)',
|
"title": 'Airplane without a Tail (Wing, Delta, etc)',
|
||||||
|
@ -1042,12 +1036,6 @@ helper.defaultsDialog = (function () {
|
||||||
value: 25
|
value: 25
|
||||||
},
|
},
|
||||||
],
|
],
|
||||||
"features": [
|
|
||||||
{
|
|
||||||
bit: 4, // Enable MOTOR_STOP
|
|
||||||
state: true
|
|
||||||
}
|
|
||||||
]
|
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"title": 'Rovers & Boats',
|
"title": 'Rovers & Boats',
|
||||||
|
@ -1205,6 +1193,7 @@ helper.defaultsDialog = (function () {
|
||||||
|
|
||||||
MIXER_CONFIG.platformType = currentMixerPreset.platform;
|
MIXER_CONFIG.platformType = currentMixerPreset.platform;
|
||||||
MIXER_CONFIG.appliedMixerPreset = selectedDefaultPreset.mixerToApply;
|
MIXER_CONFIG.appliedMixerPreset = selectedDefaultPreset.mixerToApply;
|
||||||
|
MIXER_CONFIG.motorStopOnLow = (currentMixerPreset.motorStopOnLow === true) ? true : false;
|
||||||
MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
||||||
|
|
||||||
SERVO_RULES.cleanup();
|
SERVO_RULES.cleanup();
|
||||||
|
|
43
js/fc.js
|
@ -65,6 +65,7 @@ var CONFIG,
|
||||||
BOARD_ALIGNMENT,
|
BOARD_ALIGNMENT,
|
||||||
CURRENT_METER_CONFIG,
|
CURRENT_METER_CONFIG,
|
||||||
FEATURES,
|
FEATURES,
|
||||||
|
RATE_DYNAMICS,
|
||||||
FW_APPROACH;
|
FW_APPROACH;
|
||||||
|
|
||||||
var FC = {
|
var FC = {
|
||||||
|
@ -118,8 +119,9 @@ var FC = {
|
||||||
i2cError: 0,
|
i2cError: 0,
|
||||||
activeSensors: 0,
|
activeSensors: 0,
|
||||||
mode: [],
|
mode: [],
|
||||||
profile: 0,
|
mixer_profile: -1,
|
||||||
battery_profile: 0,
|
profile: -1,
|
||||||
|
battery_profile: -1,
|
||||||
uid: [0, 0, 0],
|
uid: [0, 0, 0],
|
||||||
accelerometerTrims: [0, 0],
|
accelerometerTrims: [0, 0],
|
||||||
armingFlags: 0,
|
armingFlags: 0,
|
||||||
|
@ -196,6 +198,7 @@ var FC = {
|
||||||
MIXER_CONFIG = {
|
MIXER_CONFIG = {
|
||||||
yawMotorDirection: 0,
|
yawMotorDirection: 0,
|
||||||
yawJumpPreventionLimit: 0,
|
yawJumpPreventionLimit: 0,
|
||||||
|
motorStopOnLow: false,
|
||||||
platformType: -1,
|
platformType: -1,
|
||||||
hasFlaps: false,
|
hasFlaps: false,
|
||||||
appliedMixerPreset: -1,
|
appliedMixerPreset: -1,
|
||||||
|
@ -542,6 +545,27 @@ var FC = {
|
||||||
|
|
||||||
SAFEHOMES = new SafehomeCollection();
|
SAFEHOMES = new SafehomeCollection();
|
||||||
|
|
||||||
|
RATE_DYNAMICS = {
|
||||||
|
sensitivityCenter: null,
|
||||||
|
sensitivityEnd: null,
|
||||||
|
correctionCenter: null,
|
||||||
|
correctionEnd: null,
|
||||||
|
weightCenter: null,
|
||||||
|
weightEnd: null
|
||||||
|
};
|
||||||
|
|
||||||
|
EZ_TUNE = {
|
||||||
|
enabled: null,
|
||||||
|
filterHz: null,
|
||||||
|
axisRatio: null,
|
||||||
|
response: null,
|
||||||
|
damping: null,
|
||||||
|
stability: null,
|
||||||
|
aggressiveness: null,
|
||||||
|
rate: null,
|
||||||
|
expo: null
|
||||||
|
};
|
||||||
|
|
||||||
FW_APPROACH = new FwApproachCollection();
|
FW_APPROACH = new FwApproachCollection();
|
||||||
},
|
},
|
||||||
getOutputUsages: function() {
|
getOutputUsages: function() {
|
||||||
|
@ -557,7 +581,6 @@ var FC = {
|
||||||
getFeatures: function () {
|
getFeatures: function () {
|
||||||
var features = [
|
var features = [
|
||||||
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
|
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
|
||||||
{bit: 4, group: 'other', name: 'MOTOR_STOP'},
|
|
||||||
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
|
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
|
||||||
{bit: 7, group: 'other', name: 'GPS', haveTip: true},
|
{bit: 7, group: 'other', name: 'GPS', haveTip: true},
|
||||||
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
|
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
|
||||||
|
@ -596,7 +619,6 @@ var FC = {
|
||||||
},
|
},
|
||||||
getGpsProtocols: function () {
|
getGpsProtocols: function () {
|
||||||
return [
|
return [
|
||||||
'NMEA',
|
|
||||||
'UBLOX',
|
'UBLOX',
|
||||||
'UBLOX7',
|
'UBLOX7',
|
||||||
'MSP',
|
'MSP',
|
||||||
|
@ -619,6 +641,7 @@ var FC = {
|
||||||
'North American WAAS',
|
'North American WAAS',
|
||||||
'Japanese MSAS',
|
'Japanese MSAS',
|
||||||
'Indian GAGAN',
|
'Indian GAGAN',
|
||||||
|
'SouthPAN (AU/NZ)',
|
||||||
'Disabled'
|
'Disabled'
|
||||||
];
|
];
|
||||||
},
|
},
|
||||||
|
@ -883,6 +906,7 @@ var FC = {
|
||||||
'GVAR 5', // 35
|
'GVAR 5', // 35
|
||||||
'GVAR 6', // 36
|
'GVAR 6', // 36
|
||||||
'GVAR 7', // 37
|
'GVAR 7', // 37
|
||||||
|
'Mixer Transition', // 38
|
||||||
];
|
];
|
||||||
},
|
},
|
||||||
getServoMixInputName: function (input) {
|
getServoMixInputName: function (input) {
|
||||||
|
@ -1210,6 +1234,12 @@ var FC = {
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
|
52: {
|
||||||
|
name: "LED Pin PWM",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
|
hasOperand: [true, false],
|
||||||
|
output: "raw"
|
||||||
|
},
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
getOperandTypes: function () {
|
getOperandTypes: function () {
|
||||||
|
@ -1266,11 +1296,14 @@ var FC = {
|
||||||
30: "CRSF SNR",
|
30: "CRSF SNR",
|
||||||
31: "GPS Valid Fix",
|
31: "GPS Valid Fix",
|
||||||
32: "Loiter Radius [cm]",
|
32: "Loiter Radius [cm]",
|
||||||
33: "Active Profile",
|
33: "Active PIDProfile",
|
||||||
34: "Battery cells",
|
34: "Battery cells",
|
||||||
35: "AGL status [0/1]",
|
35: "AGL status [0/1]",
|
||||||
36: "AGL [cm]",
|
36: "AGL [cm]",
|
||||||
37: "Rangefinder [cm]",
|
37: "Rangefinder [cm]",
|
||||||
|
38: "Active MixerProfile",
|
||||||
|
39: "MixerTransition Active",
|
||||||
|
40: "Yaw [deg]"
|
||||||
38: "FW Land State"
|
38: "FW Land State"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|
109
js/gui.js
|
@ -41,7 +41,8 @@ var GUI_control = function () {
|
||||||
'advanced_tuning',
|
'advanced_tuning',
|
||||||
'mission_control',
|
'mission_control',
|
||||||
'mixer',
|
'mixer',
|
||||||
'programming'
|
'programming',
|
||||||
|
'ez_tune'
|
||||||
];
|
];
|
||||||
this.allowedTabs = this.defaultAllowedTabsWhenDisconnected;
|
this.allowedTabs = this.defaultAllowedTabsWhenDisconnected;
|
||||||
|
|
||||||
|
@ -52,6 +53,17 @@ var GUI_control = function () {
|
||||||
else if (navigator.appVersion.indexOf("Linux") != -1) this.operating_system = "Linux";
|
else if (navigator.appVersion.indexOf("Linux") != -1) this.operating_system = "Linux";
|
||||||
else if (navigator.appVersion.indexOf("X11") != -1) this.operating_system = "UNIX";
|
else if (navigator.appVersion.indexOf("X11") != -1) this.operating_system = "UNIX";
|
||||||
else this.operating_system = "Unknown";
|
else this.operating_system = "Unknown";
|
||||||
|
|
||||||
|
this.colorTable = [
|
||||||
|
"#8ecae6",
|
||||||
|
"#2a9d8f",
|
||||||
|
"#e9c46a",
|
||||||
|
"#f4a261",
|
||||||
|
"#e76f51",
|
||||||
|
"#ef476f",
|
||||||
|
"#ffc300"
|
||||||
|
];
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
// message = string
|
// message = string
|
||||||
|
@ -248,9 +260,16 @@ GUI_control.prototype.updateStatusBar = function() {
|
||||||
$('span.arming-flags').text(activeArmFlags.length ? activeArmFlags.join(', ') : '-');
|
$('span.arming-flags').text(activeArmFlags.length ? activeArmFlags.join(', ') : '-');
|
||||||
};
|
};
|
||||||
|
|
||||||
GUI_control.prototype.updateProfileChange = function() {
|
GUI_control.prototype.updateProfileChange = function(refresh) {
|
||||||
|
$('#mixerprofilechange').val(CONFIG.mixer_profile);
|
||||||
$('#profilechange').val(CONFIG.profile);
|
$('#profilechange').val(CONFIG.profile);
|
||||||
$('#batteryprofilechange').val(CONFIG.battery_profile);
|
$('#batteryprofilechange').val(CONFIG.battery_profile);
|
||||||
|
if (refresh) {
|
||||||
|
GUI.log(chrome.i18n.getMessage('loadedMixerProfile', [CONFIG.mixer_profile + 1]));
|
||||||
|
GUI.log(chrome.i18n.getMessage('pidTuning_LoadedProfile', [CONFIG.profile + 1]));
|
||||||
|
GUI.log(chrome.i18n.getMessage('loadedBatteryProfile', [CONFIG.battery_profile + 1]));
|
||||||
|
updateActivatedTab();
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
GUI_control.prototype.fillSelect = function ($element, values, currentValue, unit) {
|
GUI_control.prototype.fillSelect = function ($element, values, currentValue, unit) {
|
||||||
|
@ -383,5 +402,91 @@ GUI_control.prototype.renderLogicConditionSelect = function ($container, logicCo
|
||||||
$select.val(current).change(onChange);
|
$select.val(current).change(onChange);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
GUI_control.prototype.sliderize = function ($input, value, min, max) {
|
||||||
|
let scaledMax;
|
||||||
|
let scaledMin;
|
||||||
|
let scalingThreshold;
|
||||||
|
|
||||||
|
if ($input.data('normal-max')) {
|
||||||
|
scaledMax = max * 2;
|
||||||
|
scalingThreshold = Math.round(scaledMax * 0.8);
|
||||||
|
scaledMin = min *2;
|
||||||
|
} else {
|
||||||
|
scaledMax = max;
|
||||||
|
scaledMin = min;
|
||||||
|
scalingThreshold = scaledMax;
|
||||||
|
}
|
||||||
|
|
||||||
|
let $range = $('<input type="range" min="' + scaledMin + '" max="' + scaledMax + '" value="' + value + '"/>');
|
||||||
|
if ($input.data('step')) {
|
||||||
|
$range.attr('step', $input.data('step'));
|
||||||
|
}
|
||||||
|
$range.css({
|
||||||
|
'display': 'block',
|
||||||
|
'flex-grow': 100,
|
||||||
|
'margin-left': '1em',
|
||||||
|
'margin-right': '1em',
|
||||||
|
});
|
||||||
|
|
||||||
|
$input.attr('min', min);
|
||||||
|
$input.attr('max', max);
|
||||||
|
$input.val(parseInt(value));
|
||||||
|
$input.css({
|
||||||
|
'width': 'auto',
|
||||||
|
'min-width': '75px',
|
||||||
|
});
|
||||||
|
|
||||||
|
$input.parent().css({
|
||||||
|
'display': 'flex',
|
||||||
|
'width': '100%'
|
||||||
|
});
|
||||||
|
$range.insertAfter($input);
|
||||||
|
|
||||||
|
$input.parent().find('.helpicon').css({
|
||||||
|
'top': '5px',
|
||||||
|
'left': '-10px'
|
||||||
|
});
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Update slider to input
|
||||||
|
*/
|
||||||
|
$range.on('input', function() {
|
||||||
|
let val = $(this).val();
|
||||||
|
let normalMax = parseInt($input.data('normal-max'));
|
||||||
|
|
||||||
|
if (normalMax) {
|
||||||
|
if (val <= scalingThreshold) {
|
||||||
|
val = scaleRangeInt(val, scaledMin, scalingThreshold, min, normalMax);
|
||||||
|
} else {
|
||||||
|
val = scaleRangeInt(val, scalingThreshold + 1, scaledMax, normalMax + 1, max);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
$input.val(val);
|
||||||
|
$input.trigger('updated');
|
||||||
|
});
|
||||||
|
|
||||||
|
$input.on('change', function() {
|
||||||
|
|
||||||
|
let val = $(this).val();
|
||||||
|
let newVal;
|
||||||
|
let normalMax = parseInt($input.data('normal-max'));
|
||||||
|
if (normalMax) {
|
||||||
|
if (val <= normalMax) {
|
||||||
|
newVal = scaleRangeInt(val, min, normalMax, scaledMin, scalingThreshold);
|
||||||
|
} else {
|
||||||
|
newVal = scaleRangeInt(val, normalMax + 1, max, scalingThreshold + 1, scaledMax);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
newVal = val;
|
||||||
|
}
|
||||||
|
|
||||||
|
$range.val(newVal);
|
||||||
|
$input.trigger('updated');
|
||||||
|
});
|
||||||
|
|
||||||
|
$input.trigger('change');
|
||||||
|
};
|
||||||
|
|
||||||
// initialize object into GUI variable
|
// initialize object into GUI variable
|
||||||
var GUI = new GUI_control();
|
var GUI = new GUI_control();
|
||||||
|
|
|
@ -350,6 +350,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: true,
|
legacy: true,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
|
@ -373,6 +374,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
|
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
|
||||||
|
@ -399,6 +401,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: true,
|
legacy: true,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
hasFlaps: true,
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
|
@ -427,6 +430,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
hasFlaps: true,
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
||||||
|
@ -456,6 +460,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
hasFlaps: true,
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
|
@ -486,6 +491,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
hasFlaps: true,
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
||||||
|
@ -516,6 +522,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
|
@ -542,6 +549,7 @@ const mixerList = [
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
hasFlaps: true,
|
hasFlaps: true,
|
||||||
|
motorStopOnLow: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
|
@ -568,6 +576,7 @@ const mixerList = [
|
||||||
enabled: false,
|
enabled: false,
|
||||||
legacy: true,
|
legacy: true,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorStopOnLow: true,
|
||||||
motorMixer: [],
|
motorMixer: [],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 24
|
}, // 24
|
||||||
|
|
|
@ -6,7 +6,7 @@ var MotorMixRule = function (throttle, roll, pitch, yaw) {
|
||||||
var self = {};
|
var self = {};
|
||||||
|
|
||||||
self.fromMsp = function (mspThrottle, mspRoll, mspPitch, mspYaw) {
|
self.fromMsp = function (mspThrottle, mspRoll, mspPitch, mspYaw) {
|
||||||
throttle = mspThrottle / 1000;
|
throttle = Math.round(((mspThrottle / 1000) - 2) * 1000) / 1000;
|
||||||
roll = Math.round(((mspRoll / 1000) - 2) * 1000) / 1000;
|
roll = Math.round(((mspRoll / 1000) - 2) * 1000) / 1000;
|
||||||
pitch = Math.round(((mspPitch / 1000) - 2) * 1000) / 1000;
|
pitch = Math.round(((mspPitch / 1000) - 2) * 1000) / 1000;
|
||||||
yaw = Math.round(((mspYaw / 1000) - 2) * 1000) / 1000;
|
yaw = Math.round(((mspYaw / 1000) - 2) * 1000) / 1000;
|
||||||
|
@ -17,11 +17,11 @@ var MotorMixRule = function (throttle, roll, pitch, yaw) {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.getThrottle = function () {
|
self.getThrottle = function () {
|
||||||
return constrain(parseFloat(throttle, 10), 0, 1);
|
return constrain(parseFloat(throttle, 10), -2, 2);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.getThrottleForMsp = function () {
|
self.getThrottleForMsp = function () {
|
||||||
return self.getThrottle() * 1000;
|
return (self.getThrottle()+2) * 1000;
|
||||||
};
|
};
|
||||||
|
|
||||||
self.setThrottle = function (data) {
|
self.setThrottle = function (data) {
|
||||||
|
|
|
@ -5,6 +5,7 @@ var MotorMixerRuleCollection = function () {
|
||||||
|
|
||||||
let self = {},
|
let self = {},
|
||||||
data = [],
|
data = [],
|
||||||
|
inactiveData = [],
|
||||||
maxMotorCount = 8;
|
maxMotorCount = 8;
|
||||||
|
|
||||||
self.setMotorCount = function (value) {
|
self.setMotorCount = function (value) {
|
||||||
|
@ -16,7 +17,11 @@ var MotorMixerRuleCollection = function () {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.put = function (element) {
|
self.put = function (element) {
|
||||||
data.push(element);
|
if (data.length < self.getMotorCount()){
|
||||||
|
data.push(element);
|
||||||
|
}else{
|
||||||
|
inactiveData.push(element); //store the data for mixer_profile 2
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
self.get = function () {
|
self.get = function () {
|
||||||
|
@ -30,18 +35,25 @@ var MotorMixerRuleCollection = function () {
|
||||||
|
|
||||||
self.flush = function () {
|
self.flush = function () {
|
||||||
data = [];
|
data = [];
|
||||||
|
inactiveData = [];
|
||||||
};
|
};
|
||||||
|
|
||||||
self.cleanup = function () {
|
self.cleanup = function () {
|
||||||
var tmpData = [];
|
var tmpData = [];
|
||||||
|
var tmpInactiveData = [];
|
||||||
|
|
||||||
data.forEach(function (element) {
|
data.forEach(function (element) {
|
||||||
if (element.isUsed()) {
|
if (element.isUsed()) {
|
||||||
tmpData.push(element);
|
tmpData.push(element);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
inactiveData.forEach(function (element) {
|
||||||
|
if (element.isUsed()) {
|
||||||
|
tmpInactiveData.push(element);
|
||||||
|
}
|
||||||
|
});
|
||||||
data = tmpData;
|
data = tmpData;
|
||||||
|
inactiveData = tmpInactiveData;
|
||||||
};
|
};
|
||||||
|
|
||||||
self.inflate = function () {
|
self.inflate = function () {
|
||||||
|
@ -55,7 +67,7 @@ var MotorMixerRuleCollection = function () {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.getNumberOfConfiguredMotors = function () {
|
self.getNumberOfConfiguredMotors = function () {
|
||||||
return data.length;
|
return data.length > inactiveData.length ? data.length : inactiveData.length;
|
||||||
};
|
};
|
||||||
|
|
||||||
return self;
|
return self;
|
||||||
|
|
|
@ -180,6 +180,11 @@ var MSPCodes = {
|
||||||
MSPV2_INAV_SET_RATE_PROFILE: 0x2008,
|
MSPV2_INAV_SET_RATE_PROFILE: 0x2008,
|
||||||
MSPV2_INAV_AIR_SPEED: 0x2009,
|
MSPV2_INAV_AIR_SPEED: 0x2009,
|
||||||
MSPV2_INAV_OUTPUT_MAPPING: 0x200A,
|
MSPV2_INAV_OUTPUT_MAPPING: 0x200A,
|
||||||
|
MSP2_INAV_MC_BRAKING: 0x200B,
|
||||||
|
MSP2_INAV_SET_MC_BRAKING: 0x200C,
|
||||||
|
MSPV2_INAV_OUTPUT_MAPPING_EXT: 0x200D,
|
||||||
|
MSP2_INAV_TIMER_OUTPUT_MODE: 0x200E,
|
||||||
|
MSP2_INAV_SET_TIMER_OUTPUT_MODE: 0x200F,
|
||||||
|
|
||||||
MSP2_INAV_MIXER: 0x2010,
|
MSP2_INAV_MIXER: 0x2010,
|
||||||
MSP2_INAV_SET_MIXER: 0x2011,
|
MSP2_INAV_SET_MIXER: 0x2011,
|
||||||
|
@ -191,9 +196,6 @@ var MSPCodes = {
|
||||||
MSP2_INAV_OSD_PREFERENCES: 0x2016,
|
MSP2_INAV_OSD_PREFERENCES: 0x2016,
|
||||||
MSP2_INAV_OSD_SET_PREFERENCES: 0x2017,
|
MSP2_INAV_OSD_SET_PREFERENCES: 0x2017,
|
||||||
|
|
||||||
MSP2_INAV_MC_BRAKING: 0x200B,
|
|
||||||
MSP2_INAV_SET_MC_BRAKING: 0x200C,
|
|
||||||
|
|
||||||
MSP2_INAV_SELECT_BATTERY_PROFILE: 0x2018,
|
MSP2_INAV_SELECT_BATTERY_PROFILE: 0x2018,
|
||||||
|
|
||||||
MSP2_INAV_DEBUG: 0x2019,
|
MSP2_INAV_DEBUG: 0x2019,
|
||||||
|
@ -217,6 +219,7 @@ var MSPCodes = {
|
||||||
MSP2_INAV_SET_PROGRAMMING_PID: 0x2029,
|
MSP2_INAV_SET_PROGRAMMING_PID: 0x2029,
|
||||||
MSP2_INAV_PROGRAMMING_PID_STATUS: 0x202A,
|
MSP2_INAV_PROGRAMMING_PID_STATUS: 0x202A,
|
||||||
|
|
||||||
|
|
||||||
MSP2_PID: 0x2030,
|
MSP2_PID: 0x2030,
|
||||||
MSP2_SET_PID: 0x2031,
|
MSP2_SET_PID: 0x2031,
|
||||||
|
|
||||||
|
@ -236,6 +239,15 @@ var MSPCodes = {
|
||||||
MSP2_INAV_LED_STRIP_CONFIG_EX: 0x2048,
|
MSP2_INAV_LED_STRIP_CONFIG_EX: 0x2048,
|
||||||
MSP2_INAV_SET_LED_STRIP_CONFIG_EX: 0x2049,
|
MSP2_INAV_SET_LED_STRIP_CONFIG_EX: 0x2049,
|
||||||
|
|
||||||
|
MSP2_INAV_RATE_DYNAMICS: 0x2060,
|
||||||
|
MSP2_INAV_SET_RATE_DYNAMICS: 0x2061,
|
||||||
|
|
||||||
|
MSP2_INAV_EZ_TUNE: 0x2070,
|
||||||
|
MSP2_INAV_EZ_TUNE_SET: 0x2071,
|
||||||
|
|
||||||
|
MSP2_INAV_SELECT_MIXER_PROFILE: 0x2080
|
||||||
|
MSP2_INAV_SET_LED_STRIP_CONFIG_EX: 0x2049,
|
||||||
|
|
||||||
MSP2_INAV_FW_APPROACH: 0x204A,
|
MSP2_INAV_FW_APPROACH: 0x204A,
|
||||||
MSP2_INAV_SET_FW_APPROACH: 0x204B
|
MSP2_INAV_SET_FW_APPROACH: 0x204B
|
||||||
};
|
};
|
||||||
|
|
|
@ -68,6 +68,7 @@ var mspHelper = (function (gui) {
|
||||||
color;
|
color;
|
||||||
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
|
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
|
||||||
case MSPCodes.MSPV2_INAV_STATUS:
|
case MSPCodes.MSPV2_INAV_STATUS:
|
||||||
|
let profile_changed = false;
|
||||||
CONFIG.cycleTime = data.getUint16(offset, true);
|
CONFIG.cycleTime = data.getUint16(offset, true);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
CONFIG.i2cError = data.getUint16(offset, true);
|
CONFIG.i2cError = data.getUint16(offset, true);
|
||||||
|
@ -76,13 +77,28 @@ var mspHelper = (function (gui) {
|
||||||
offset += 2;
|
offset += 2;
|
||||||
CONFIG.cpuload = data.getUint16(offset, true);
|
CONFIG.cpuload = data.getUint16(offset, true);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
|
|
||||||
profile_byte = data.getUint8(offset++)
|
profile_byte = data.getUint8(offset++)
|
||||||
CONFIG.profile = profile_byte & 0x0F;
|
let profile = profile_byte & 0x0F;
|
||||||
CONFIG.battery_profile = (profile_byte & 0xF0) >> 4;
|
profile_changed |= (profile !== CONFIG.profile) && (CONFIG.profile !==-1);
|
||||||
|
CONFIG.profile = profile;
|
||||||
|
|
||||||
|
let battery_profile = (profile_byte & 0xF0) >> 4;
|
||||||
|
profile_changed |= (battery_profile !== CONFIG.battery_profile) && (CONFIG.battery_profile !==-1);
|
||||||
|
CONFIG.battery_profile = battery_profile;
|
||||||
|
|
||||||
CONFIG.armingFlags = data.getUint32(offset, true);
|
CONFIG.armingFlags = data.getUint32(offset, true);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
|
|
||||||
|
//As there are 8 bytes for mspBoxModeFlags (number of bytes is actually variable)
|
||||||
|
//read mixer profile as the last byte in the the message
|
||||||
|
profile_byte = data.getUint8(dataHandler.message_length_expected - 1);
|
||||||
|
let mixer_profile = profile_byte & 0x0F;
|
||||||
|
profile_changed |= (mixer_profile !== CONFIG.mixer_profile) && (CONFIG.mixer_profile !==-1);
|
||||||
|
CONFIG.mixer_profile = mixer_profile;
|
||||||
|
|
||||||
gui.updateStatusBar();
|
gui.updateStatusBar();
|
||||||
gui.updateProfileChange();
|
gui.updateProfileChange(profile_changed);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_ACTIVEBOXES:
|
case MSPCodes.MSP_ACTIVEBOXES:
|
||||||
|
@ -1453,7 +1469,8 @@ var mspHelper = (function (gui) {
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP2_INAV_MIXER:
|
case MSPCodes.MSP2_INAV_MIXER:
|
||||||
MIXER_CONFIG.yawMotorDirection = data.getInt8(0);
|
MIXER_CONFIG.yawMotorDirection = data.getInt8(0);
|
||||||
MIXER_CONFIG.yawJumpPreventionLimit = data.getUint16(1, true);
|
MIXER_CONFIG.yawJumpPreventionLimit = data.getUint8(1, true);
|
||||||
|
MIXER_CONFIG.motorStopOnLow = data.getUint8(2, true);
|
||||||
MIXER_CONFIG.platformType = data.getInt8(3);
|
MIXER_CONFIG.platformType = data.getInt8(3);
|
||||||
MIXER_CONFIG.hasFlaps = data.getInt8(4);
|
MIXER_CONFIG.hasFlaps = data.getInt8(4);
|
||||||
MIXER_CONFIG.appliedMixerPreset = data.getInt16(5, true);
|
MIXER_CONFIG.appliedMixerPreset = data.getInt16(5, true);
|
||||||
|
@ -1482,7 +1499,32 @@ var mspHelper = (function (gui) {
|
||||||
case MSPCodes.MSPV2_INAV_OUTPUT_MAPPING:
|
case MSPCodes.MSPV2_INAV_OUTPUT_MAPPING:
|
||||||
OUTPUT_MAPPING.flush();
|
OUTPUT_MAPPING.flush();
|
||||||
for (i = 0; i < data.byteLength; ++i)
|
for (i = 0; i < data.byteLength; ++i)
|
||||||
OUTPUT_MAPPING.put(data.getUint8(i));
|
OUTPUT_MAPPING.put({
|
||||||
|
'timerId': i,
|
||||||
|
'usageFlags': data.getUint8(i)});
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSPV2_INAV_OUTPUT_MAPPING_EXT:
|
||||||
|
OUTPUT_MAPPING.flush();
|
||||||
|
for (i = 0; i < data.byteLength; i += 2) {
|
||||||
|
timerId = data.getUint8(i);
|
||||||
|
usageFlags = data.getUint8(i + 1);
|
||||||
|
OUTPUT_MAPPING.put(
|
||||||
|
{
|
||||||
|
'timerId': timerId,
|
||||||
|
'usageFlags': usageFlags
|
||||||
|
});
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_TIMER_OUTPUT_MODE:
|
||||||
|
if(data.byteLength > 2) {
|
||||||
|
OUTPUT_MAPPING.flushTimerOverrides();
|
||||||
|
}
|
||||||
|
for (i = 0; i < data.byteLength; i += 2) {
|
||||||
|
timerId = data.getUint8(i);
|
||||||
|
outputMode = data.getUint8(i + 1);
|
||||||
|
OUTPUT_MAPPING.setTimerOverride(timerId, outputMode);
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP2_INAV_MC_BRAKING:
|
case MSPCodes.MSP2_INAV_MC_BRAKING:
|
||||||
|
@ -1552,6 +1594,35 @@ var mspHelper = (function (gui) {
|
||||||
console.log('FW Approach saved');
|
console.log('FW Approach saved');
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_RATE_DYNAMICS:
|
||||||
|
RATE_DYNAMICS.sensitivityCenter = data.getUint8(0);
|
||||||
|
RATE_DYNAMICS.sensitivityEnd = data.getUint8(1);
|
||||||
|
RATE_DYNAMICS.correctionCenter = data.getUint8(2);
|
||||||
|
RATE_DYNAMICS.correctionEnd = data.getUint8(3);
|
||||||
|
RATE_DYNAMICS.weightCenter = data.getUint8(4);
|
||||||
|
RATE_DYNAMICS.weightEnd = data.getUint8(5);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_SET_RATE_DYNAMICS:
|
||||||
|
console.log('Rate dynamics saved');
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_EZ_TUNE:
|
||||||
|
EZ_TUNE.enabled = data.getUint8(0);
|
||||||
|
EZ_TUNE.filterHz = data.getUint16(1, true);
|
||||||
|
EZ_TUNE.axisRatio = data.getUint8(3);
|
||||||
|
EZ_TUNE.response = data.getUint8(4);
|
||||||
|
EZ_TUNE.damping = data.getUint8(5);
|
||||||
|
EZ_TUNE.stability = data.getUint8(6);
|
||||||
|
EZ_TUNE.aggressiveness = data.getUint8(7);
|
||||||
|
EZ_TUNE.rate = data.getUint8(8);
|
||||||
|
EZ_TUNE.expo = data.getUint8(9);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_EZ_TUNE_SET:
|
||||||
|
console.log('EzTune settings saved');
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
console.log('Unknown code detected: ' + dataHandler.code);
|
console.log('Unknown code detected: ' + dataHandler.code);
|
||||||
} else {
|
} else {
|
||||||
|
@ -2149,8 +2220,8 @@ var mspHelper = (function (gui) {
|
||||||
|
|
||||||
case MSPCodes.MSP2_INAV_SET_MIXER:
|
case MSPCodes.MSP2_INAV_SET_MIXER:
|
||||||
buffer.push(MIXER_CONFIG.yawMotorDirection);
|
buffer.push(MIXER_CONFIG.yawMotorDirection);
|
||||||
buffer.push(lowByte(MIXER_CONFIG.yawJumpPreventionLimit));
|
buffer.push(MIXER_CONFIG.yawJumpPreventionLimit);
|
||||||
buffer.push(highByte(MIXER_CONFIG.yawJumpPreventionLimit));
|
buffer.push(MIXER_CONFIG.motorStopOnLow);
|
||||||
buffer.push(MIXER_CONFIG.platformType);
|
buffer.push(MIXER_CONFIG.platformType);
|
||||||
buffer.push(MIXER_CONFIG.hasFlaps);
|
buffer.push(MIXER_CONFIG.hasFlaps);
|
||||||
buffer.push(lowByte(MIXER_CONFIG.appliedMixerPreset));
|
buffer.push(lowByte(MIXER_CONFIG.appliedMixerPreset));
|
||||||
|
@ -2179,6 +2250,31 @@ var mspHelper = (function (gui) {
|
||||||
buffer.push(BRAKING_CONFIG.bankAngle);
|
buffer.push(BRAKING_CONFIG.bankAngle);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_SET_RATE_DYNAMICS:
|
||||||
|
buffer.push(RATE_DYNAMICS.sensitivityCenter);
|
||||||
|
buffer.push(RATE_DYNAMICS.sensitivityEnd);
|
||||||
|
buffer.push(RATE_DYNAMICS.correctionCenter);
|
||||||
|
buffer.push(RATE_DYNAMICS.correctionEnd);
|
||||||
|
buffer.push(RATE_DYNAMICS.weightCenter);
|
||||||
|
buffer.push(RATE_DYNAMICS.weightEnd);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_EZ_TUNE_SET:
|
||||||
|
|
||||||
|
buffer.push(EZ_TUNE.enabled);
|
||||||
|
buffer.push(lowByte(EZ_TUNE.filterHz));
|
||||||
|
buffer.push(highByte(EZ_TUNE.filterHz));
|
||||||
|
buffer.push(EZ_TUNE.axisRatio);
|
||||||
|
buffer.push(EZ_TUNE.response);
|
||||||
|
buffer.push(EZ_TUNE.damping);
|
||||||
|
buffer.push(EZ_TUNE.stability);
|
||||||
|
buffer.push(EZ_TUNE.aggressiveness);
|
||||||
|
buffer.push(EZ_TUNE.rate);
|
||||||
|
buffer.push(EZ_TUNE.expo);
|
||||||
|
console.log(buffer);
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -2840,6 +2936,47 @@ var mspHelper = (function (gui) {
|
||||||
MSP.send_message(MSPCodes.MSPV2_INAV_OUTPUT_MAPPING, false, false, callback);
|
MSP.send_message(MSPCodes.MSPV2_INAV_OUTPUT_MAPPING, false, false, callback);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.loadOutputMappingExt = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSPV2_INAV_OUTPUT_MAPPING_EXT, false, false, callback);
|
||||||
|
};
|
||||||
|
|
||||||
|
self.loadTimerOutputModes = function(callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_TIMER_OUTPUT_MODE, false, false, callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
self.sendTimerOutputModes = function(callback) {
|
||||||
|
var nextFunction = send_next_output_mode;
|
||||||
|
var idIndex = 0;
|
||||||
|
|
||||||
|
var overrideIds = OUTPUT_MAPPING.getUsedTimerIds();
|
||||||
|
|
||||||
|
if (overrideIds.length == 0) {
|
||||||
|
onCompleteCallback();
|
||||||
|
} else {
|
||||||
|
send_next_output_mode();
|
||||||
|
}
|
||||||
|
|
||||||
|
function send_next_output_mode() {
|
||||||
|
|
||||||
|
var timerId = overrideIds[idIndex];
|
||||||
|
|
||||||
|
var outputMode = OUTPUT_MAPPING.getTimerOverride(timerId);
|
||||||
|
|
||||||
|
var buffer = [];
|
||||||
|
buffer.push(timerId);
|
||||||
|
buffer.push(outputMode);
|
||||||
|
|
||||||
|
// prepare for next iteration
|
||||||
|
idIndex++;
|
||||||
|
if (idIndex == overrideIds.length) {
|
||||||
|
nextFunction = callback;
|
||||||
|
|
||||||
|
}
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_SET_TIMER_OUTPUT_MODE, buffer, false, nextFunction);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
self.loadBatteryConfig = function (callback) {
|
self.loadBatteryConfig = function (callback) {
|
||||||
MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
|
MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
|
||||||
};
|
};
|
||||||
|
@ -3023,7 +3160,7 @@ var mspHelper = (function (gui) {
|
||||||
if (waypointId < MISSION_PLANNER.getCountBusyPoints()) {
|
if (waypointId < MISSION_PLANNER.getCountBusyPoints()) {
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, loadWaypoint);
|
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, loadWaypoint);
|
||||||
} else {
|
} else {
|
||||||
GUI.log('Receive time: ' + (new Date().getTime() - startTime) + 'ms');
|
GUI.log(chrome.i18n.getMessage('ReceiveTime') + (new Date().getTime() - startTime) + 'ms');
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
|
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -3045,7 +3182,7 @@ var mspHelper = (function (gui) {
|
||||||
};
|
};
|
||||||
|
|
||||||
function endMission() {
|
function endMission() {
|
||||||
GUI.log('Send time: ' + (new Date().getTime() - startTime) + 'ms');
|
GUI.log(chrome.i18n.getMessage('SendTime') + (new Date().getTime() - startTime) + 'ms');
|
||||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -3363,6 +3500,22 @@ var mspHelper = (function (gui) {
|
||||||
MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
|
MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.loadRateDynamics = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_RATE_DYNAMICS, false, false, callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
self.saveRateDynamics = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_SET_RATE_DYNAMICS, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_RATE_DYNAMICS), false, callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
self.loadEzTune = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_EZ_TUNE, false, false, callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
self.saveEzTune = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_EZ_TUNE_SET, mspHelper.crunch(MSPCodes.MSP2_INAV_EZ_TUNE_SET), false, callback);
|
||||||
|
}
|
||||||
|
|
||||||
self.loadParameterGroups = function (callback) {
|
self.loadParameterGroups = function (callback) {
|
||||||
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
|
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
|
||||||
var groups = [];
|
var groups = [];
|
||||||
|
|
|
@ -3,22 +3,63 @@
|
||||||
|
|
||||||
let OutputMappingCollection = function () {
|
let OutputMappingCollection = function () {
|
||||||
let self = {},
|
let self = {},
|
||||||
data = [];
|
data = [],
|
||||||
|
timerOverrides = {};
|
||||||
|
|
||||||
const TIM_USE_ANY = 0;
|
const TIM_USE_ANY = 0;
|
||||||
const TIM_USE_PPM = 0;
|
const TIM_USE_PPM = 0;
|
||||||
const TIM_USE_PWM = 1;
|
const TIM_USE_PWM = 1;
|
||||||
const TIM_USE_MC_MOTOR = 2; // Multicopter motor output
|
const TIM_USE_MOTOR = 2; // Motor output
|
||||||
const TIM_USE_MC_SERVO = 3; // Multicopter servo output (i.e. TRI)
|
const TIM_USE_SERVO = 3; // Servo output (i.e. TRI)
|
||||||
const TIM_USE_MC_CHNFW = 4; // Deprecated and not used after removal of CHANNEL_FORWARDING feature
|
//const TIM_USE_MC_CHNFW = 4; // Deprecated and not used after removal of CHANNEL_FORWARDING feature
|
||||||
const TIM_USE_FW_MOTOR = 5;
|
//const TIM_USE_FW_MOTOR = 5;
|
||||||
const TIM_USE_FW_SERVO = 6;
|
//const TIM_USE_FW_SERVO = 6;
|
||||||
const TIM_USE_LED = 24;
|
const TIM_USE_LED = 24;
|
||||||
const TIM_USE_BEEPER = 25;
|
const TIM_USE_BEEPER = 25;
|
||||||
|
|
||||||
const OUTPUT_TYPE_MOTOR = 0;
|
const OUTPUT_TYPE_MOTOR = 0;
|
||||||
const OUTPUT_TYPE_SERVO = 1;
|
const OUTPUT_TYPE_SERVO = 1;
|
||||||
|
|
||||||
|
self.TIMER_OUTPUT_MODE_AUTO = 0;
|
||||||
|
self.TIMER_OUTPUT_MODE_MOTORS = 1;
|
||||||
|
self.TIMER_OUTPUT_MODE_SERVOS = 2;
|
||||||
|
|
||||||
|
self.flushTimerOverrides = function() {
|
||||||
|
timerOverrides = {};
|
||||||
|
}
|
||||||
|
|
||||||
|
self.setTimerOverride = function (timer, outputMode) {
|
||||||
|
timerOverrides[timer] = outputMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
self.getTimerOverride = function (timer) {
|
||||||
|
return timerOverrides[timer];
|
||||||
|
}
|
||||||
|
|
||||||
|
self.getTimerColor = function (timer) {
|
||||||
|
let timerIndex = OUTPUT_MAPPING.getUsedTimerIds().indexOf(String(timer));
|
||||||
|
|
||||||
|
return GUI.colorTable[timerIndex % GUI.colorTable.length];
|
||||||
|
}
|
||||||
|
|
||||||
|
self.getOutputTimerColor = function (output) {
|
||||||
|
let timerId = OUTPUT_MAPPING.getTimerId(output);
|
||||||
|
|
||||||
|
return self.getTimerColor(timerId);
|
||||||
|
}
|
||||||
|
|
||||||
|
self.getUsedTimerIds = function (timer) {
|
||||||
|
let used = {};
|
||||||
|
let outputCount = self.getOutputCount();
|
||||||
|
|
||||||
|
for (let i = 0; i < outputCount; ++i) {
|
||||||
|
let timerId = self.getTimerId(i);
|
||||||
|
used[timerId] = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return Object.keys(used).sort((a, b) => a - b);
|
||||||
|
}
|
||||||
|
|
||||||
function getTimerMap(isMR, motors, servos) {
|
function getTimerMap(isMR, motors, servos) {
|
||||||
let timerMap = [],
|
let timerMap = [],
|
||||||
motorsToGo = motors,
|
motorsToGo = motors,
|
||||||
|
@ -27,24 +68,13 @@ let OutputMappingCollection = function () {
|
||||||
for (let i = 0; i < data.length; i++) {
|
for (let i = 0; i < data.length; i++) {
|
||||||
timerMap[i] = null;
|
timerMap[i] = null;
|
||||||
|
|
||||||
if (isMR) {
|
if (servosToGo > 0 && bit_check(data[i]['usageFlags'], TIM_USE_SERVO)) {
|
||||||
if (servosToGo > 0 && bit_check(data[i], TIM_USE_MC_SERVO)) {
|
servosToGo--;
|
||||||
servosToGo--;
|
timerMap[i] = OUTPUT_TYPE_SERVO;
|
||||||
timerMap[i] = OUTPUT_TYPE_SERVO;
|
} else if (motorsToGo > 0 && bit_check(data[i]['usageFlags'], TIM_USE_MOTOR)) {
|
||||||
} else if (motorsToGo > 0 && bit_check(data[i], TIM_USE_MC_MOTOR)) {
|
motorsToGo--;
|
||||||
motorsToGo--;
|
timerMap[i] = OUTPUT_TYPE_MOTOR;
|
||||||
timerMap[i] = OUTPUT_TYPE_MOTOR;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
if (servosToGo > 0 && bit_check(data[i], TIM_USE_FW_SERVO)) {
|
|
||||||
servosToGo--;
|
|
||||||
timerMap[i] = OUTPUT_TYPE_SERVO;
|
|
||||||
} else if (motorsToGo > 0 && bit_check(data[i], TIM_USE_FW_MOTOR)) {
|
|
||||||
motorsToGo--;
|
|
||||||
timerMap[i] = OUTPUT_TYPE_MOTOR;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return timerMap;
|
return timerMap;
|
||||||
|
@ -70,7 +100,6 @@ let OutputMappingCollection = function () {
|
||||||
outputMap[i] = "Servo " + servos[currentServoIndex];
|
outputMap[i] = "Servo " + servos[currentServoIndex];
|
||||||
currentServoIndex++;
|
currentServoIndex++;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return outputMap;
|
return outputMap;
|
||||||
|
@ -89,10 +118,8 @@ let OutputMappingCollection = function () {
|
||||||
|
|
||||||
for (let i = 0; i < data.length; i++) {
|
for (let i = 0; i < data.length; i++) {
|
||||||
if (
|
if (
|
||||||
bit_check(data[i], TIM_USE_MC_MOTOR) ||
|
bit_check(data[i]['usageFlags'], TIM_USE_MOTOR) ||
|
||||||
bit_check(data[i], TIM_USE_MC_SERVO) ||
|
bit_check(data[i]['usageFlags'], TIM_USE_SERVO)
|
||||||
bit_check(data[i], TIM_USE_FW_MOTOR) ||
|
|
||||||
bit_check(data[i], TIM_USE_FW_SERVO)
|
|
||||||
) {
|
) {
|
||||||
retVal++;
|
retVal++;
|
||||||
};
|
};
|
||||||
|
@ -104,10 +131,8 @@ let OutputMappingCollection = function () {
|
||||||
function getFirstOutputOffset() {
|
function getFirstOutputOffset() {
|
||||||
for (let i = 0; i < data.length; i++) {
|
for (let i = 0; i < data.length; i++) {
|
||||||
if (
|
if (
|
||||||
bit_check(data[i], TIM_USE_MC_MOTOR) ||
|
bit_check(data[i]['usageFlags'], TIM_USE_MOTOR) ||
|
||||||
bit_check(data[i], TIM_USE_MC_SERVO) ||
|
bit_check(data[i]['usageFlags'], TIM_USE_SERVO)
|
||||||
bit_check(data[i], TIM_USE_FW_MOTOR) ||
|
|
||||||
bit_check(data[i], TIM_USE_FW_SERVO)
|
|
||||||
) {
|
) {
|
||||||
return i;
|
return i;
|
||||||
}
|
}
|
||||||
|
@ -115,6 +140,10 @@ let OutputMappingCollection = function () {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function getTimerId(outputIndex) {
|
||||||
|
return data[outputIndex]['timerId'];
|
||||||
|
}
|
||||||
|
|
||||||
function getOutput(servoIndex, bit) {
|
function getOutput(servoIndex, bit) {
|
||||||
|
|
||||||
let offset = getFirstOutputOffset();
|
let offset = getFirstOutputOffset();
|
||||||
|
@ -122,7 +151,7 @@ let OutputMappingCollection = function () {
|
||||||
let lastFound = 0;
|
let lastFound = 0;
|
||||||
|
|
||||||
for (let i = offset; i < data.length; i++) {
|
for (let i = offset; i < data.length; i++) {
|
||||||
if (bit_check(data[i], bit)) {
|
if (bit_check(data[i]['usageFlags'], bit)) {
|
||||||
if (lastFound == servoIndex) {
|
if (lastFound == servoIndex) {
|
||||||
return i - offset + 1;
|
return i - offset + 1;
|
||||||
} else {
|
} else {
|
||||||
|
@ -134,12 +163,16 @@ let OutputMappingCollection = function () {
|
||||||
return null;
|
return null;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
self.getTimerId = function(outputIndex) {
|
||||||
|
return getTimerId(outputIndex)
|
||||||
|
}
|
||||||
|
|
||||||
self.getFwServoOutput = function (servoIndex) {
|
self.getFwServoOutput = function (servoIndex) {
|
||||||
return getOutput(servoIndex, TIM_USE_FW_SERVO);
|
return getOutput(servoIndex, TIM_USE_SERVO);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.getMrServoOutput = function (index) {
|
self.getMrServoOutput = function (index) {
|
||||||
return getOutput(index, TIM_USE_MC_SERVO);
|
return getOutput(index, TIM_USE_SERVO);
|
||||||
};
|
};
|
||||||
|
|
||||||
return self;
|
return self;
|
||||||
|
|
|
@ -81,7 +81,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
|
|
||||||
self.initialize();
|
self.initialize();
|
||||||
} else {
|
} else {
|
||||||
GUI.log('<span style="color: red">Failed</span> to open serial port');
|
GUI.log(chrome.i18n.getMessage('failedToOpenSerialPort'));
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
|
@ -108,7 +108,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
retries++;
|
retries++;
|
||||||
if (retries > maxRetries) {
|
if (retries > maxRetries) {
|
||||||
clearInterval(interval);
|
clearInterval(interval);
|
||||||
GUI.log('<span style="color: red">Failed</span> to flash ' + port);
|
GUI.log(chrome.i18n.getMessage('failedToFlash') + port);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// Check for DFU devices
|
// Check for DFU devices
|
||||||
|
@ -145,7 +145,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
GUI.log('<span style="color: red">Failed</span> to open serial port');
|
GUI.log(chrome.i18n.getMessage('failedToOpenSerialPort'));
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
|
@ -257,6 +257,7 @@ function onValidFirmware()
|
||||||
|
|
||||||
$('#tabs ul.mode-connected .tab_setup a').click();
|
$('#tabs ul.mode-connected .tab_setup a').click();
|
||||||
|
|
||||||
|
updateEzTuneTabVisibility(true);
|
||||||
updateFirmwareVersion();
|
updateFirmwareVersion();
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
|
|
@ -5,6 +5,7 @@ let ServoMixerRuleCollection = function () {
|
||||||
|
|
||||||
let self = {},
|
let self = {},
|
||||||
data = [],
|
data = [],
|
||||||
|
inactiveData = [],
|
||||||
maxServoCount = 16;
|
maxServoCount = 16;
|
||||||
|
|
||||||
self.setServoCount = function (value) {
|
self.setServoCount = function (value) {
|
||||||
|
@ -20,7 +21,11 @@ let ServoMixerRuleCollection = function () {
|
||||||
}
|
}
|
||||||
|
|
||||||
self.put = function (element) {
|
self.put = function (element) {
|
||||||
data.push(element);
|
if (data.length < self.getServoRulesCount()) {
|
||||||
|
data.push(element);
|
||||||
|
}else{
|
||||||
|
inactiveData.push(element); //store the data for mixer_profile 2
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
self.get = function () {
|
self.get = function () {
|
||||||
|
@ -34,18 +39,24 @@ let ServoMixerRuleCollection = function () {
|
||||||
|
|
||||||
self.flush = function () {
|
self.flush = function () {
|
||||||
data = [];
|
data = [];
|
||||||
|
inactiveData = [];
|
||||||
};
|
};
|
||||||
|
|
||||||
self.cleanup = function () {
|
self.cleanup = function () {
|
||||||
var tmpData = [];
|
var tmpData = [];
|
||||||
|
var tmpInactiveData = [];
|
||||||
data.forEach(function (element) {
|
data.forEach(function (element) {
|
||||||
if (element.isUsed()) {
|
if (element.isUsed()) {
|
||||||
tmpData.push(element);
|
tmpData.push(element);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
inactiveData.forEach(function (element) {
|
||||||
|
if (element.isUsed()) {
|
||||||
|
tmpInactiveData.push(element);
|
||||||
|
}
|
||||||
|
});
|
||||||
data = tmpData;
|
data = tmpData;
|
||||||
|
inactiveData = tmpInactiveData;
|
||||||
};
|
};
|
||||||
|
|
||||||
self.inflate = function () {
|
self.inflate = function () {
|
||||||
|
@ -69,6 +80,15 @@ let ServoMixerRuleCollection = function () {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
for (let ruleIndex in inactiveData) {
|
||||||
|
if (inactiveData.hasOwnProperty(ruleIndex)) {
|
||||||
|
let rule = inactiveData[ruleIndex];
|
||||||
|
|
||||||
|
if (rule.getTarget() == servoId && rule.isUsed()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
return false;
|
return false;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -106,12 +126,17 @@ let ServoMixerRuleCollection = function () {
|
||||||
out.push(rule.getTarget());
|
out.push(rule.getTarget());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
for (let ruleIndex in inactiveData) {
|
||||||
|
if (inactiveData.hasOwnProperty(ruleIndex)) {
|
||||||
|
let rule = inactiveData[ruleIndex];
|
||||||
|
out.push(rule.getTarget());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
let unique = [...new Set(out)];
|
|
||||||
|
|
||||||
return unique.sort(function(a, b) {
|
let minIndex = Math.min(...out);
|
||||||
return a-b;
|
let maxIndex = Math.max(...out);
|
||||||
});
|
return Array.from({ length: maxIndex - minIndex + 1 }, (_, index) => minIndex + index);
|
||||||
}
|
}
|
||||||
|
|
||||||
self.getNextUnusedIndex = function() {
|
self.getNextUnusedIndex = function() {
|
||||||
|
|
|
@ -85,88 +85,7 @@ var Settings = (function () {
|
||||||
input.attr('maxlength', s.setting.max);
|
input.attr('maxlength', s.setting.max);
|
||||||
} else if (input.data('presentation') == 'range') {
|
} else if (input.data('presentation') == 'range') {
|
||||||
|
|
||||||
let scaledMax;
|
GUI.sliderize(input, s.value, s.setting.min, s.setting.max);
|
||||||
let scaledMin;
|
|
||||||
let scalingThreshold;
|
|
||||||
|
|
||||||
if (input.data('normal-max')) {
|
|
||||||
scaledMax = s.setting.max * 2;
|
|
||||||
scalingThreshold = Math.round(scaledMax * 0.8);
|
|
||||||
scaledMin = s.setting.min *2;
|
|
||||||
} else {
|
|
||||||
scaledMax = s.setting.max;
|
|
||||||
scaledMin = s.setting.min;
|
|
||||||
scalingThreshold = scaledMax;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
let $range = $('<input type="range" min="' + scaledMin + '" max="' + scaledMax + '" value="' + s.value + '"/>');
|
|
||||||
if (input.data('step')) {
|
|
||||||
$range.attr('step', input.data('step'));
|
|
||||||
}
|
|
||||||
$range.css({
|
|
||||||
'display': 'block',
|
|
||||||
'flex-grow': 100,
|
|
||||||
'margin-left': '1em',
|
|
||||||
'margin-right': '1em',
|
|
||||||
});
|
|
||||||
|
|
||||||
input.attr('min', s.setting.min);
|
|
||||||
input.attr('max', s.setting.max);
|
|
||||||
input.val(parseInt(s.value));
|
|
||||||
input.css({
|
|
||||||
'width': 'auto',
|
|
||||||
'min-width': '75px',
|
|
||||||
});
|
|
||||||
|
|
||||||
input.parent().css({
|
|
||||||
'display': 'flex',
|
|
||||||
'width': '100%'
|
|
||||||
});
|
|
||||||
$range.insertAfter(input);
|
|
||||||
|
|
||||||
input.parent().find('.helpicon').css({
|
|
||||||
'top': '5px',
|
|
||||||
'left': '-10px'
|
|
||||||
});
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Update slider to input
|
|
||||||
*/
|
|
||||||
$range.on('input', function() {
|
|
||||||
let val = $(this).val();
|
|
||||||
let normalMax = parseInt(input.data('normal-max'));
|
|
||||||
|
|
||||||
if (normalMax) {
|
|
||||||
if (val <= scalingThreshold) {
|
|
||||||
val = scaleRangeInt(val, scaledMin, scalingThreshold, s.setting.min, normalMax);
|
|
||||||
} else {
|
|
||||||
val = scaleRangeInt(val, scalingThreshold + 1, scaledMax, normalMax + 1, s.setting.max);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
input.val(val);
|
|
||||||
});
|
|
||||||
|
|
||||||
input.on('change', function() {
|
|
||||||
|
|
||||||
let val = $(this).val();
|
|
||||||
let newVal;
|
|
||||||
let normalMax = parseInt(input.data('normal-max'));
|
|
||||||
if (normalMax) {
|
|
||||||
if (val <= normalMax) {
|
|
||||||
newVal = scaleRangeInt(val, s.setting.min, normalMax, scaledMin, scalingThreshold);
|
|
||||||
} else {
|
|
||||||
newVal = scaleRangeInt(val, normalMax + 1, s.setting.max, scalingThreshold + 1, scaledMax);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
newVal = val;
|
|
||||||
}
|
|
||||||
|
|
||||||
$range.val(newVal);
|
|
||||||
});
|
|
||||||
|
|
||||||
input.trigger('change');
|
|
||||||
|
|
||||||
} else if (s.setting.type == 'float') {
|
} else if (s.setting.type == 'float') {
|
||||||
input.attr('type', 'number');
|
input.attr('type', 'number');
|
||||||
|
|
25
main.css
|
@ -60,6 +60,10 @@ a.disabled {
|
||||||
transition: none;
|
transition: none;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.inputRequiredWarning {
|
||||||
|
border: 3px solid #d40000 !important;
|
||||||
|
}
|
||||||
|
|
||||||
.cf_doc_version_bt a {
|
.cf_doc_version_bt a {
|
||||||
padding: 1px 9px 1px 9px;
|
padding: 1px 9px 1px 9px;
|
||||||
margin-top: -45px;
|
margin-top: -45px;
|
||||||
|
@ -1639,7 +1643,7 @@ dialog {
|
||||||
/* fixing padding for all Tabs*/
|
/* fixing padding for all Tabs*/
|
||||||
.tab-setup, .tab-landing, .tab-adjustments, .tab-auxiliary, .tab-cli, .tab-configuration, .tab-failsafe, .tab-onboard_logging,
|
.tab-setup, .tab-landing, .tab-adjustments, .tab-auxiliary, .tab-cli, .tab-configuration, .tab-failsafe, .tab-onboard_logging,
|
||||||
.tab-firmware_flasher, .tab-gps, .tab-magnetometer, .tab-help, .tab-led-strip, .tab-logging, .tab-modes, .tab-motors, .tab-pid_tuning,
|
.tab-firmware_flasher, .tab-gps, .tab-magnetometer, .tab-help, .tab-led-strip, .tab-logging, .tab-modes, .tab-motors, .tab-pid_tuning,
|
||||||
.tab-ports, .tab-receiver, .tab-sensors, .tab-servos, .tab-osd, .tab-calibration {
|
.tab-ports, .tab-receiver, .tab-sensors, .tab-servos, .tab-osd, .tab-calibration, .tab-ez_tune {
|
||||||
height: 100%;
|
height: 100%;
|
||||||
position: relative;
|
position: relative;
|
||||||
}
|
}
|
||||||
|
@ -1681,7 +1685,7 @@ dialog {
|
||||||
color: white;
|
color: white;
|
||||||
font-size: 10px;
|
font-size: 10px;
|
||||||
margin-top: 20px;
|
margin-top: 20px;
|
||||||
width: 269px;
|
width: 410px;
|
||||||
float: right;
|
float: right;
|
||||||
margin-right: 10px;
|
margin-right: 10px;
|
||||||
line-height: 12px;
|
line-height: 12px;
|
||||||
|
@ -1696,6 +1700,15 @@ dialog {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#mixer_profile_change {
|
||||||
|
color: white;
|
||||||
|
margin-top: 16px;
|
||||||
|
width: 130px;
|
||||||
|
float: left;
|
||||||
|
margin-right: 10px;
|
||||||
|
line-height: 12px;
|
||||||
|
}
|
||||||
|
|
||||||
#profile_change {
|
#profile_change {
|
||||||
color: white;
|
color: white;
|
||||||
margin-top: 16px;
|
margin-top: 16px;
|
||||||
|
@ -2271,3 +2284,11 @@ ol li {
|
||||||
.controlProfileHighlightActive {
|
.controlProfileHighlightActive {
|
||||||
background-color: #d5ebfe !important ;
|
background-color: #d5ebfe !important ;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.no-border {
|
||||||
|
border: none !important;
|
||||||
|
}
|
||||||
|
|
||||||
|
.bold {
|
||||||
|
font-weight: bold;
|
||||||
|
}
|
81
main.html
|
@ -23,11 +23,11 @@
|
||||||
<div class="headerbar">
|
<div class="headerbar">
|
||||||
<div id="logo">
|
<div id="logo">
|
||||||
<div class="logo_text">
|
<div class="logo_text">
|
||||||
CONFIGURATOR
|
<span i18n="mainLogoText"></span>
|
||||||
<div class="version"></div>
|
<div class="version"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="logo_text_firmware">
|
<div class="logo_text_firmware">
|
||||||
FC FIRMWARE
|
<span i18n="mainLogoTextFirmware"></span>
|
||||||
<div class="firmware_version"></div>
|
<div class="firmware_version"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -43,13 +43,13 @@
|
||||||
<div id="portsinput">
|
<div id="portsinput">
|
||||||
<div class="portsinput__row">
|
<div class="portsinput__row">
|
||||||
<div id="port-override-option" class="portsinput__top-element portsinput__top-element--port-override">
|
<div id="port-override-option" class="portsinput__top-element portsinput__top-element--port-override">
|
||||||
<label id="port-override-label" for="port-override">Port: </label>
|
<label id="port-override-label" for="port-override" i18n="mainPortOverrideLabel"></label>
|
||||||
<input id="port-override" type="text" value="/dev/rfcomm0" />
|
<input id="port-override" type="text" value="/dev/rfcomm0" />
|
||||||
</div>
|
</div>
|
||||||
<div class="dropdown dropdown-dark portsinput__top-element">
|
<div class="dropdown dropdown-dark portsinput__top-element">
|
||||||
<!--suppress HtmlFormInputWithoutLabel -->
|
<!--suppress HtmlFormInputWithoutLabel -->
|
||||||
<select class="dropdown-select" id="port" title="Port">
|
<select class="dropdown-select" id="port" title="Port">
|
||||||
<option value="manual">Manual</option>
|
<option value="manual" i18n="mainManual"></option>
|
||||||
<!-- port list gets generated here -->
|
<!-- port list gets generated here -->
|
||||||
</select>
|
</select>
|
||||||
</div>
|
</div>
|
||||||
|
@ -81,20 +81,30 @@
|
||||||
</div>
|
</div>
|
||||||
<div class="header-wrapper">
|
<div class="header-wrapper">
|
||||||
<div id="dataflash_wrapper_global">
|
<div id="dataflash_wrapper_global">
|
||||||
<div class="noflash_global" align="center">No dataflash <br>chip found</div>
|
<div class="noflash_global" align="center" i18n="sensorDataFlashNotFound"></div>
|
||||||
<ul class="dataflash-contents_global">
|
<ul class="dataflash-contents_global">
|
||||||
<li class="dataflash-free_global">
|
<li class="dataflash-free_global">
|
||||||
<div class="legend">Dataflash: free space</div>
|
<div class="legend" i18n="sensorDataFlashFreeSpace"></div>
|
||||||
</li>
|
</li>
|
||||||
</ul>
|
</ul>
|
||||||
|
<div id="mixer_profile_change">
|
||||||
|
<div class="dropdown dropdown-dark">
|
||||||
|
<form name="mixer-profile-change" id="mixer-profile-change">
|
||||||
|
<select class="dropdown-select" id="mixerprofilechange">
|
||||||
|
<option value="0" i18n="mixerProfile1"></option>
|
||||||
|
<option value="1" i18n="mixerProfile2"></option>
|
||||||
|
</select>
|
||||||
|
</form>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
<div id="profile_change">
|
<div id="profile_change">
|
||||||
<div class="dropdown dropdown-dark">
|
<div class="dropdown dropdown-dark">
|
||||||
<form name="profile-change" id="profile-change">
|
<form name="profile-change" id="profile-change">
|
||||||
<!--suppress HtmlFormInputWithoutLabel -->
|
<!--suppress HtmlFormInputWithoutLabel -->
|
||||||
<select class="dropdown-select" id="profilechange">
|
<select class="dropdown-select" id="profilechange">
|
||||||
<option value="0">Profile 1</option>
|
<option value="0" i18n="sensorProfile1"></option>
|
||||||
<option value="1">Profile 2</option>
|
<option value="1" i18n="sensorProfile2"></option>
|
||||||
<option value="2">Profile 3</option>
|
<option value="2" i18n="sensorProfile3"></option>
|
||||||
</select>
|
</select>
|
||||||
</form>
|
</form>
|
||||||
</div>
|
</div>
|
||||||
|
@ -104,9 +114,9 @@
|
||||||
<form name="battery-profile-change" id="battery-profile-change">
|
<form name="battery-profile-change" id="battery-profile-change">
|
||||||
<!--suppress HtmlFormInputWithoutLabel -->
|
<!--suppress HtmlFormInputWithoutLabel -->
|
||||||
<select class="dropdown-select" id="batteryprofilechange">
|
<select class="dropdown-select" id="batteryprofilechange">
|
||||||
<option value="0">Battery profile 1</option>
|
<option value="0" i18n="sensorBatteryProfile1"></option>
|
||||||
<option value="1">Battery profile 2</option>
|
<option value="1" i18n="sensorBatteryProfile2"></option>
|
||||||
<option value="2">Battery profile 3</option>
|
<option value="2" i18n="sensorBatteryProfile3"></option>
|
||||||
</select>
|
</select>
|
||||||
</form>
|
</form>
|
||||||
</div>
|
</div>
|
||||||
|
@ -114,29 +124,30 @@
|
||||||
</div>
|
</div>
|
||||||
<div id="sensor-status" class="sensor_state mode-connected">
|
<div id="sensor-status" class="sensor_state mode-connected">
|
||||||
<ul>
|
<ul>
|
||||||
<li class="gyro" title="Gyroscope">
|
<li class="gyro" i18n_title="sensorStatusGyro">
|
||||||
<div class="gyroicon">Gyro</div>
|
<div class="gyroicon" i18n="sensorStatusGyroShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="accel" title="Accelerometer">
|
<li class="accel" i18n_title="sensorStatusAccel">
|
||||||
<div class="accicon">Accel</div>
|
<div class="accicon" i18n="sensorStatusAccelShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="mag" title="Magnetometer">
|
<li class="mag" i18n_title="sensorStatusMag">
|
||||||
<div class="magicon">Mag</div>
|
<div class="magicon" i18n="sensorStatusMagShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="baro" title="Barometer">
|
<li class="baro" i18n_title="sensorStatusBaro">
|
||||||
<div class="baroicon">Baro</div>
|
<div class="baroicon" i18n="sensorStatusBaroShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="gps" title="GPS">
|
<li class="gps" i18n_title="sensorStatusGPS">
|
||||||
<div class="gpsicon">GPS</div>
|
<div class="gpsicon" i18n="sensorStatusGPSShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="opflow" title="Optical flow">
|
|
||||||
<div class="opflowicon">Flow</div>
|
<li class="opflow" i18n_title="sensorOpticalFlow">
|
||||||
|
<div class="opflowicon" i18n="sensorOpticalFlowShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="sonar" title="Sonar / Range finder">
|
<li class="sonar" i18n_title="sensorStatusSonar">
|
||||||
<div class="sonaricon">Sonar</div>
|
<div class="sonaricon" i18n="sensorStatusSonarShort"></div>
|
||||||
</li>
|
</li>
|
||||||
<li class="airspeed" title="Airspeed">
|
<li class="airspeed" i18n_title="sensorAirspeed">
|
||||||
<div class="airspeedicon">Speed</div>
|
<div class="airspeedicon" i18n="sensorAirspeedShort"></div>
|
||||||
</li>
|
</li>
|
||||||
</ul>
|
</ul>
|
||||||
</div>
|
</div>
|
||||||
|
@ -146,7 +157,7 @@
|
||||||
<div class="battery-status"></div>
|
<div class="battery-status"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="battery-legend">Battery voltage</div>
|
<div class="battery-legend" i18n="sensorBatteryVoltage"></div>
|
||||||
<div class="bottomStatusIcons">
|
<div class="bottomStatusIcons">
|
||||||
<div class="armedicon cf_tip" data-i18n_title="mainHelpArmed"></div>
|
<div class="armedicon cf_tip" data-i18n_title="mainHelpArmed"></div>
|
||||||
<div class="failsafeicon cf_tip" data-i18n_title="mainHelpFailsafe"></div>
|
<div class="failsafeicon cf_tip" data-i18n_title="mainHelpFailsafe"></div>
|
||||||
|
@ -158,7 +169,7 @@
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
<div id="log">
|
<div id="log">
|
||||||
<div class="logswitch">
|
<div class="logswitch">
|
||||||
<a href="#" id="showlog">Show Log</a>
|
<a href="#" id="showlog" i18n="mainShowLog"></a>
|
||||||
</div>
|
</div>
|
||||||
<div id="scrollicon"></div>
|
<div id="scrollicon"></div>
|
||||||
<div class="wrapper"></div>
|
<div class="wrapper"></div>
|
||||||
|
@ -204,6 +215,9 @@
|
||||||
<li class="tab_failsafe">
|
<li class="tab_failsafe">
|
||||||
<a href="#" data-i18n="tabFailsafe" class="tabicon ic_failsafe" title="Failsafe"></a>
|
<a href="#" data-i18n="tabFailsafe" class="tabicon ic_failsafe" title="Failsafe"></a>
|
||||||
</li>
|
</li>
|
||||||
|
<li class="tab_ez_tune">
|
||||||
|
<a href="#" data-i18n="tabEzTune" class="tabicon ic_wizzard"></a>
|
||||||
|
</li>
|
||||||
<li class="tab_pid_tuning">
|
<li class="tab_pid_tuning">
|
||||||
<a href="#" data-i18n="tabPidTuning" class="tabicon ic_pid" title="PID Tuning"></a>
|
<a href="#" data-i18n="tabPidTuning" class="tabicon ic_pid" title="PID Tuning"></a>
|
||||||
</li>
|
</li>
|
||||||
|
@ -250,8 +264,7 @@
|
||||||
<a href="#" data-i18n="tabCLI" class="tabicon ic_cli" title="CLI"></a>
|
<a href="#" data-i18n="tabCLI" class="tabicon ic_cli" title="CLI"></a>
|
||||||
</li>
|
</li>
|
||||||
|
|
||||||
<!--<li class=""><a href="#" class="tabicon ic_advanced">Advanced (spare icon)</a></li>-->
|
<!-- <li class=""><a href="#" class="tabicon ic_advanced">Advanced (spare icon)</a></li> -->
|
||||||
<!--<li class=""><a href="#" class="tabicon ic_wizzard">Wizzard (spare icon)</a></li>-->
|
|
||||||
</ul>
|
</ul>
|
||||||
</div>
|
</div>
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
|
@ -294,7 +307,7 @@
|
||||||
</div>
|
</div>
|
||||||
<div id="cache">
|
<div id="cache">
|
||||||
<div class="data-loading">
|
<div class="data-loading">
|
||||||
<p>Waiting for data ...</p>
|
<p i18n="waitingForData"></p>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -317,4 +330,4 @@
|
||||||
</div>
|
</div>
|
||||||
</body>
|
</body>
|
||||||
|
|
||||||
</html>
|
</html>
|
47
main.js
|
@ -85,9 +85,9 @@ $(document).ready(function () {
|
||||||
}
|
}
|
||||||
|
|
||||||
// alternative - window.navigator.appVersion.match(/Chrome\/([0-9.]*)/)[1];
|
// alternative - window.navigator.appVersion.match(/Chrome\/([0-9.]*)/)[1];
|
||||||
GUI.log('Running - OS: <strong>' + GUI.operating_system + '</strong>, ' +
|
GUI.log(chrome.i18n.getMessage('getRunningOS') + GUI.operating_system + '</strong>, ' +
|
||||||
'Chrome: <strong>' + window.navigator.appVersion.replace(/.*Chrome\/([0-9.]*).*/, "$1") + '</strong>, ' +
|
'Chrome: <strong>' + window.navigator.appVersion.replace(/.*Chrome\/([0-9.]*).*/, "$1") + '</strong>, ' +
|
||||||
'Configurator: <strong>' + chrome.runtime.getManifest().version + '</strong>');
|
chrome.i18n.getMessage('getConfiguratorVersion') + chrome.runtime.getManifest().version + '</strong>');
|
||||||
|
|
||||||
$('#status-bar .version').text(chrome.runtime.getManifest().version);
|
$('#status-bar .version').text(chrome.runtime.getManifest().version);
|
||||||
$('#logo .version').text(chrome.runtime.getManifest().version);
|
$('#logo .version').text(chrome.runtime.getManifest().version);
|
||||||
|
@ -301,6 +301,9 @@ $(document).ready(function () {
|
||||||
case 'cli':
|
case 'cli':
|
||||||
TABS.cli.initialize(content_ready);
|
TABS.cli.initialize(content_ready);
|
||||||
break;
|
break;
|
||||||
|
case 'ez_tune':
|
||||||
|
TABS.ez_tune.initialize(content_ready);
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
console.log('Tab not found:' + tab);
|
console.log('Tab not found:' + tab);
|
||||||
|
@ -540,11 +543,24 @@ $(document).ready(function () {
|
||||||
|
|
||||||
state = true;
|
state = true;
|
||||||
}
|
}
|
||||||
$(this).text(state ? 'Hide Log' : 'Show Log');
|
$(this).html(state ? chrome.i18n.getMessage("mainHideLog") : chrome.i18n.getMessage("mainShowLog"));
|
||||||
$(this).data('state', state);
|
$(this).data('state', state);
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
|
var mixerprofile_e = $('#mixerprofilechange');
|
||||||
|
|
||||||
|
mixerprofile_e.change(function () {
|
||||||
|
var mixerprofile = parseInt($(this).val());
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_SELECT_MIXER_PROFILE, [mixerprofile], false, function () {
|
||||||
|
GUI.log(chrome.i18n.getMessage('loadedMixerProfile', [mixerprofile + 1]));
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
|
||||||
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
|
GUI.handleReconnect();
|
||||||
|
});
|
||||||
|
});
|
||||||
|
});
|
||||||
|
|
||||||
var profile_e = $('#profilechange');
|
var profile_e = $('#profilechange');
|
||||||
|
|
||||||
profile_e.change(function () {
|
profile_e.change(function () {
|
||||||
|
@ -701,3 +717,28 @@ function updateFirmwareVersion() {
|
||||||
globalSettings.docsTreeLocation = 'https://github.com/iNavFlight/inav/blob/master/docs/';
|
globalSettings.docsTreeLocation = 'https://github.com/iNavFlight/inav/blob/master/docs/';
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function updateEzTuneTabVisibility(loadMixerConfig) {
|
||||||
|
let useEzTune = true;
|
||||||
|
if (CONFIGURATOR.connectionValid) {
|
||||||
|
if (loadMixerConfig) {
|
||||||
|
mspHelper.loadMixerConfig(function() {
|
||||||
|
if (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) {
|
||||||
|
$('.tab_ez_tune').removeClass("is-hidden");
|
||||||
|
} else {
|
||||||
|
$('.tab_ez_tune').addClass("is-hidden");
|
||||||
|
useEzTune = false;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
} else {
|
||||||
|
if (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) {
|
||||||
|
$('.tab_ez_tune').removeClass("is-hidden");
|
||||||
|
} else {
|
||||||
|
$('.tab_ez_tune').addClass("is-hidden");
|
||||||
|
useEzTune = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return useEzTune;
|
||||||
|
}
|
|
@ -1,7 +1,7 @@
|
||||||
{
|
{
|
||||||
"manifest_version": 2,
|
"manifest_version": 2,
|
||||||
"minimum_chrome_version": "38",
|
"minimum_chrome_version": "38",
|
||||||
"version": "6.1.0",
|
"version": "7.0.0-RC2",
|
||||||
"author": "Several",
|
"author": "Several",
|
||||||
"name": "INAV - Configurator",
|
"name": "INAV - Configurator",
|
||||||
"short_name": "INAV",
|
"short_name": "INAV",
|
||||||
|
|
4
package-lock.json
generated
|
@ -1,12 +1,12 @@
|
||||||
{
|
{
|
||||||
"name": "inav-configurator",
|
"name": "inav-configurator",
|
||||||
"version": "6.1.0",
|
"version": "7.0.0",
|
||||||
"lockfileVersion": 2,
|
"lockfileVersion": 2,
|
||||||
"requires": true,
|
"requires": true,
|
||||||
"packages": {
|
"packages": {
|
||||||
"": {
|
"": {
|
||||||
"name": "inav-configurator",
|
"name": "inav-configurator",
|
||||||
"version": "6.1.0",
|
"version": "7.0.0",
|
||||||
"license": "GPL-3.0",
|
"license": "GPL-3.0",
|
||||||
"dependencies": {
|
"dependencies": {
|
||||||
"archiver": "^2.0.3",
|
"archiver": "^2.0.3",
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
{
|
{
|
||||||
"name": "inav-configurator",
|
"name": "inav-configurator",
|
||||||
"description": "INAV Configurator",
|
"description": "INAV Configurator",
|
||||||
"version": "6.1.0",
|
"version": "7.0.0-RC2",
|
||||||
"main": "main.html",
|
"main": "main.html",
|
||||||
"default_locale": "en",
|
"default_locale": "en",
|
||||||
"scripts": {
|
"scripts": {
|
||||||
|
|
6903
resources/models/fc.gltf
Normal file
|
@ -1,51 +1,38 @@
|
||||||
<?xml version="1.0" encoding="UTF-8"?>
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
<!-- Public domain (CC-BY-SA if you or your laws insist), generated by Jonathan Hudson's svg_model_motors.rb -->
|
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||||
<svg xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" width="200pt" height="200pt" viewBox="0 0 200 200" version="1.1">
|
<svg width="100%" height="100%" viewBox="0 0 200 200" version="1.1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" xml:space="preserve" xmlns:serif="http://www.serif.com/" style="fill-rule:evenodd;clip-rule:evenodd;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:10;">
|
||||||
<defs>
|
<g id="surface6">
|
||||||
<g>
|
<path d="M40,40L160,40M100,40L100,160" style="fill:none;fill-rule:nonzero;stroke:rgb(185,185,185);stroke-width:28px;"/>
|
||||||
<symbol overflow="visible" id="glyph0-0">
|
<path d="M128,160C128,175.465 115.465,188 100,188C84.535,188 72,175.465 72,160C72,144.535 84.535,132 100,132C115.465,132 128,144.535 128,160M80.199,140.199L80.199,123.398M80.199,140.199L97,142.215" style="fill:none;fill-rule:nonzero;stroke:rgb(55,168,219);stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
<path style="stroke:none;" d=""/>
|
<g id="glyph0-1" transform="matrix(1,0,0,1,93,167)">
|
||||||
</symbol>
|
<g>
|
||||||
<symbol overflow="visible" id="glyph0-1">
|
<path d="M2.68,-13.863L2.68,-15.75C4.457,-15.922 5.695,-16.211 6.398,-16.617C7.102,-17.023 7.625,-17.984 7.969,-19.496L9.914,-19.496L9.914,0L7.289,0L7.289,-13.863L2.68,-13.863Z" style="fill-rule:nonzero;"/>
|
||||||
<path style="stroke:none;" d="M 2.679688 -13.863281 L 2.679688 -15.75 C 4.457031 -15.921875 5.695312 -16.210938 6.398438 -16.617188 C 7.101562 -17.023438 7.625 -17.984375 7.96875 -19.496094 L 9.914062 -19.496094 L 9.914062 0 L 7.289062 0 L 7.289062 -13.863281 Z M 2.679688 -13.863281 "/>
|
</g>
|
||||||
</symbol>
|
</g>
|
||||||
<symbol overflow="visible" id="glyph0-2">
|
<path d="M188,40C188,55.465 175.465,68 160,68C144.535,68 132,55.465 132,40C132,24.535 144.535,12 160,12C175.465,12 188,24.535 188,40M140.199,20.199L140.199,3.398M140.199,20.199L157,22.215" style="fill:none;fill-rule:nonzero;stroke:rgb(55,168,219);stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
<path style="stroke:none;" d="M 1.921875 -4.402344 C 2.527344 -5.652344 3.710938 -6.785156 5.46875 -7.804688 L 8.09375 -9.324219 C 9.269531 -10.007812 10.09375 -10.589844 10.570312 -11.074219 C 11.316406 -11.832031 11.6875 -12.695312 11.6875 -13.671875 C 11.6875 -14.8125 11.347656 -15.714844 10.664062 -16.386719 C 9.980469 -17.054688 9.070312 -17.390625 7.929688 -17.390625 C 6.242188 -17.390625 5.078125 -16.753906 4.429688 -15.476562 C 4.082031 -14.792969 3.890625 -13.84375 3.855469 -12.632812 L 1.351562 -12.632812 C 1.378906 -14.335938 1.695312 -15.726562 2.296875 -16.804688 C 3.363281 -18.699219 5.246094 -19.648438 7.945312 -19.648438 C 10.1875 -19.648438 11.824219 -19.039062 12.859375 -17.828125 C 13.894531 -16.617188 14.410156 -15.265625 14.410156 -13.78125 C 14.410156 -12.214844 13.859375 -10.875 12.757812 -9.761719 C 12.117188 -9.113281 10.972656 -8.332031 9.324219 -7.410156 L 7.453125 -6.371094 C 6.558594 -5.878906 5.855469 -5.410156 5.34375 -4.960938 C 4.433594 -4.167969 3.859375 -3.289062 3.625 -2.324219 L 14.3125 -2.324219 L 14.3125 0 L 0.875 0 C 0.964844 -1.6875 1.316406 -3.152344 1.921875 -4.402344 Z M 1.921875 -4.402344 "/>
|
<g id="glyph0-2" transform="matrix(1,0,0,1,153,47)">
|
||||||
</symbol>
|
<g>
|
||||||
<symbol overflow="visible" id="glyph0-3">
|
<path d="M1.922,-4.402C2.527,-5.652 3.711,-6.785 5.469,-7.805L8.094,-9.324C9.27,-10.008 10.094,-10.59 10.57,-11.074C11.316,-11.832 11.688,-12.695 11.688,-13.672C11.688,-14.813 11.348,-15.715 10.664,-16.387C9.98,-17.055 9.07,-17.391 7.93,-17.391C6.242,-17.391 5.078,-16.754 4.43,-15.477C4.082,-14.793 3.891,-13.844 3.855,-12.633L1.352,-12.633C1.379,-14.336 1.695,-15.727 2.297,-16.805C3.363,-18.699 5.246,-19.648 7.945,-19.648C10.188,-19.648 11.824,-19.039 12.859,-17.828C13.895,-16.617 14.41,-15.266 14.41,-13.781C14.41,-12.215 13.859,-10.875 12.758,-9.762C12.117,-9.113 10.973,-8.332 9.324,-7.41L7.453,-6.371C6.559,-5.879 5.855,-5.41 5.344,-4.961C4.434,-4.168 3.859,-3.289 3.625,-2.324L14.313,-2.324L14.313,0L0.875,0C0.965,-1.688 1.316,-3.152 1.922,-4.402Z" style="fill-rule:nonzero;"/>
|
||||||
<path style="stroke:none;" d="M 2.234375 -1.375 C 1.191406 -2.644531 0.671875 -4.191406 0.671875 -6.015625 L 3.242188 -6.015625 C 3.351562 -4.75 3.585938 -3.828125 3.953125 -3.253906 C 4.589844 -2.222656 5.742188 -1.710938 7.410156 -1.710938 C 8.703125 -1.710938 9.742188 -2.054688 10.527344 -2.75 C 11.3125 -3.441406 11.703125 -4.335938 11.703125 -5.429688 C 11.703125 -6.777344 11.289062 -7.71875 10.464844 -8.257812 C 9.640625 -8.796875 8.496094 -9.0625 7.027344 -9.0625 C 6.863281 -9.0625 6.695312 -9.0625 6.527344 -9.058594 C 6.359375 -9.054688 6.1875 -9.046875 6.015625 -9.039062 L 6.015625 -11.210938 C 6.269531 -11.183594 6.484375 -11.164062 6.65625 -11.15625 C 6.832031 -11.148438 7.019531 -11.140625 7.21875 -11.140625 C 8.140625 -11.140625 8.894531 -11.289062 9.488281 -11.578125 C 10.527344 -12.089844 11.046875 -13 11.046875 -14.3125 C 11.046875 -15.289062 10.699219 -16.042969 10.007812 -16.570312 C 9.316406 -17.097656 8.507812 -17.363281 7.585938 -17.363281 C 5.945312 -17.363281 4.8125 -16.816406 4.183594 -15.722656 C 3.835938 -15.121094 3.640625 -14.265625 3.59375 -13.152344 L 1.164062 -13.152344 C 1.164062 -14.609375 1.453125 -15.851562 2.039062 -16.871094 C 3.039062 -18.695312 4.804688 -19.605469 7.328125 -19.605469 C 9.324219 -19.605469 10.867188 -19.160156 11.960938 -18.273438 C 13.054688 -17.382812 13.601562 -16.097656 13.601562 -14.410156 C 13.601562 -13.207031 13.28125 -12.230469 12.632812 -11.484375 C 12.230469 -11.019531 11.710938 -10.65625 11.074219 -10.390625 C 12.105469 -10.109375 12.910156 -9.5625 13.488281 -8.757812 C 14.066406 -7.949219 14.355469 -6.964844 14.355469 -5.796875 C 14.355469 -3.929688 13.742188 -2.40625 12.507812 -1.230469 C 11.277344 -0.0546875 9.535156 0.53125 7.273438 0.53125 C 4.957031 0.53125 3.277344 -0.101562 2.234375 -1.375 Z M 2.234375 -1.375 "/>
|
</g>
|
||||||
</symbol>
|
</g>
|
||||||
<symbol overflow="visible" id="glyph1-0">
|
<g transform="matrix(0.0166389,-0.999862,-0.999862,-0.0166389,80.5581,80.9602)">
|
||||||
<path style="stroke:none;" d=""/>
|
<path d="M68,40C68,55.465 55.465,68 40,68C24.535,68 12,55.465 12,40C12,24.535 24.535,12 40,12C55.465,12 68,24.535 68,40M59.801,20.199L57.785,37M59.801,20.199L76.602,20.199" style="fill:none;fill-rule:nonzero;stroke:rgb(55,168,219);stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
</symbol>
|
</g>
|
||||||
<symbol overflow="visible" id="glyph1-1">
|
<g id="glyph0-3" transform="matrix(1,0,0,1,33,47)">
|
||||||
<path style="stroke:none;" d="M 2.234375 -3.703125 C 2.269531 -3.050781 2.425781 -2.523438 2.695312 -2.117188 C 3.210938 -1.355469 4.121094 -0.976562 5.421875 -0.976562 C 6.003906 -0.976562 6.535156 -1.058594 7.015625 -1.226562 C 7.941406 -1.550781 8.40625 -2.128906 8.40625 -2.960938 C 8.40625 -3.585938 8.210938 -4.03125 7.820312 -4.296875 C 7.425781 -4.558594 6.804688 -4.785156 5.960938 -4.976562 L 4.40625 -5.328125 C 3.390625 -5.558594 2.671875 -5.808594 2.25 -6.085938 C 1.519531 -6.566406 1.15625 -7.28125 1.15625 -8.234375 C 1.15625 -9.265625 1.511719 -10.113281 2.226562 -10.773438 C 2.941406 -11.433594 3.949219 -11.765625 5.257812 -11.765625 C 6.460938 -11.765625 7.484375 -11.476562 8.324219 -10.894531 C 9.164062 -10.3125 9.585938 -9.386719 9.585938 -8.109375 L 8.125 -8.109375 C 8.046875 -8.722656 7.878906 -9.195312 7.625 -9.523438 C 7.152344 -10.121094 6.347656 -10.421875 5.210938 -10.421875 C 4.292969 -10.421875 3.636719 -10.230469 3.234375 -9.84375 C 2.832031 -9.457031 2.632812 -9.011719 2.632812 -8.5 C 2.632812 -7.9375 2.867188 -7.527344 3.335938 -7.265625 C 3.644531 -7.097656 4.339844 -6.890625 5.421875 -6.640625 L 7.03125 -6.273438 C 7.808594 -6.097656 8.40625 -5.855469 8.828125 -5.546875 C 9.558594 -5.011719 9.921875 -4.230469 9.921875 -3.210938 C 9.921875 -1.941406 9.460938 -1.03125 8.535156 -0.484375 C 7.609375 0.0625 6.535156 0.335938 5.3125 0.335938 C 3.886719 0.335938 2.769531 -0.0273438 1.960938 -0.757812 C 1.152344 -1.480469 0.757812 -2.464844 0.773438 -3.703125 Z M 2.234375 -3.703125 "/>
|
<g>
|
||||||
</symbol>
|
<path d="M2.234,-1.375C1.191,-2.645 0.672,-4.191 0.672,-6.016L3.242,-6.016C3.352,-4.75 3.586,-3.828 3.953,-3.254C4.59,-2.223 5.742,-1.711 7.41,-1.711C8.703,-1.711 9.742,-2.055 10.527,-2.75C11.313,-3.441 11.703,-4.336 11.703,-5.43C11.703,-6.777 11.289,-7.719 10.465,-8.258C9.641,-8.797 8.496,-9.063 7.027,-9.063C6.863,-9.063 6.695,-9.063 6.527,-9.059C6.359,-9.055 6.188,-9.047 6.016,-9.039L6.016,-11.211C6.27,-11.184 6.484,-11.164 6.656,-11.156C6.832,-11.148 7.02,-11.141 7.219,-11.141C8.141,-11.141 8.895,-11.289 9.488,-11.578C10.527,-12.09 11.047,-13 11.047,-14.313C11.047,-15.289 10.699,-16.043 10.008,-16.57C9.316,-17.098 8.508,-17.363 7.586,-17.363C5.945,-17.363 4.813,-16.816 4.184,-15.723C3.836,-15.121 3.641,-14.266 3.594,-13.152L1.164,-13.152C1.164,-14.609 1.453,-15.852 2.039,-16.871C3.039,-18.695 4.805,-19.605 7.328,-19.605C9.324,-19.605 10.867,-19.16 11.961,-18.273C13.055,-17.383 13.602,-16.098 13.602,-14.41C13.602,-13.207 13.281,-12.23 12.633,-11.484C12.23,-11.02 11.711,-10.656 11.074,-10.391C12.105,-10.109 12.91,-9.563 13.488,-8.758C14.066,-7.949 14.355,-6.965 14.355,-5.797C14.355,-3.93 13.742,-2.406 12.508,-1.23C11.277,-0.055 9.535,0.531 7.273,0.531C4.957,0.531 3.277,-0.102 2.234,-1.375Z" style="fill-rule:nonzero;"/>
|
||||||
<symbol overflow="visible" id="glyph1-2">
|
</g>
|
||||||
<path style="stroke:none;" d="M 1.53125 -7.921875 L 1.53125 -9 C 2.546875 -9.097656 3.253906 -9.265625 3.65625 -9.496094 C 4.058594 -9.726562 4.355469 -10.277344 4.554688 -11.140625 L 5.664062 -11.140625 L 5.664062 0 L 4.164062 0 L 4.164062 -7.921875 Z M 1.53125 -7.921875 "/>
|
</g>
|
||||||
</symbol>
|
<rect x="140" y="140" width="28" height="28" style="fill:none;fill-rule:nonzero;stroke:black;stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
</g>
|
<g>
|
||||||
</defs>
|
<g id="glyph1-1" transform="matrix(1,0,0,1,144,160)">
|
||||||
<g id="surface6">
|
<path d="M2.234,-3.703C2.27,-3.051 2.426,-2.523 2.695,-2.117C3.211,-1.355 4.121,-0.977 5.422,-0.977C6.004,-0.977 6.535,-1.059 7.016,-1.227C7.941,-1.551 8.406,-2.129 8.406,-2.961C8.406,-3.586 8.211,-4.031 7.82,-4.297C7.426,-4.559 6.805,-4.785 5.961,-4.977L4.406,-5.328C3.391,-5.559 2.672,-5.809 2.25,-6.086C1.52,-6.566 1.156,-7.281 1.156,-8.234C1.156,-9.266 1.512,-10.113 2.227,-10.773C2.941,-11.434 3.949,-11.766 5.258,-11.766C6.461,-11.766 7.484,-11.477 8.324,-10.895C9.164,-10.313 9.586,-9.387 9.586,-8.109L8.125,-8.109C8.047,-8.723 7.879,-9.195 7.625,-9.523C7.152,-10.121 6.348,-10.422 5.211,-10.422C4.293,-10.422 3.637,-10.23 3.234,-9.844C2.832,-9.457 2.633,-9.012 2.633,-8.5C2.633,-7.938 2.867,-7.527 3.336,-7.266C3.645,-7.098 4.34,-6.891 5.422,-6.641L7.031,-6.273C7.809,-6.098 8.406,-5.855 8.828,-5.547C9.559,-5.012 9.922,-4.23 9.922,-3.211C9.922,-1.941 9.461,-1.031 8.535,-0.484C7.609,0.063 6.535,0.336 5.313,0.336C3.887,0.336 2.77,-0.027 1.961,-0.758C1.152,-1.48 0.758,-2.465 0.773,-3.703L2.234,-3.703Z" style="fill-rule:nonzero;"/>
|
||||||
<path style="fill:none;stroke-width:28;stroke-linecap:round;stroke-linejoin:round;stroke:rgb(72.941176%,72.941176%,72.941176%);stroke-opacity:1;stroke-miterlimit:10;" d="M 40 40 L 160 40 M 100 40 L 100 160 "/>
|
</g>
|
||||||
<path style="fill:none;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke:rgb(55,168,219);stroke-opacity:1;stroke-miterlimit:10;" d="M 128 160 C 128 175.464844 115.464844 188 100 188 C 84.535156 188 72 175.464844 72 160 C 72 144.535156 84.535156 132 100 132 C 115.464844 132 128 144.535156 128 160 M 80.199219 140.199219 L 80.199219 123.398438 M 80.199219 140.199219 L 97 142.214844 "/>
|
<g id="glyph1-2" transform="matrix(1,0,0,1,154.672,160)">
|
||||||
<g style="fill:rgb(0%,0%,0%);fill-opacity:1;">
|
<path d="M1.531,-7.922L1.531,-9C2.547,-9.098 3.254,-9.266 3.656,-9.496C4.059,-9.727 4.355,-10.277 4.555,-11.141L5.664,-11.141L5.664,0L4.164,0L4.164,-7.922L1.531,-7.922Z" style="fill-rule:nonzero;"/>
|
||||||
<use xlink:href="#glyph0-1" x="93" y="167"/>
|
</g>
|
||||||
</g>
|
</g>
|
||||||
<path style="fill:none;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke:rgb(55,168,219);stroke-opacity:1;stroke-miterlimit:10;" d="M 188 40 C 188 55.464844 175.464844 68 160 68 C 144.535156 68 132 55.464844 132 40 C 132 24.535156 144.535156 12 160 12 C 175.464844 12 188 24.535156 188 40 M 140.199219 20.199219 L 140.199219 3.398438 M 140.199219 20.199219 L 157 22.214844 "/>
|
<path d="M100,70L100,110" style="fill:none;fill-rule:nonzero;stroke:rgb(250,6,0);stroke-width:12px;stroke-linecap:butt;stroke-linejoin:bevel;"/>
|
||||||
<g style="fill:rgb(0%,0%,0%);fill-opacity:1;">
|
<path d="M100,65L85,80L115,80L100,65" style="fill:rgb(250,6,0);fill-rule:nonzero;"/>
|
||||||
<use xlink:href="#glyph0-2" x="153" y="47"/>
|
</g>
|
||||||
</g>
|
|
||||||
<path style="fill:none;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke:rgb(55,168,219);stroke-opacity:1;stroke-miterlimit:10;" d="M 68 40 C 68 55.464844 55.464844 68 40 68 C 24.535156 68 12 55.464844 12 40 C 12 24.535156 24.535156 12 40 12 C 55.464844 12 68 24.535156 68 40 M 59.800781 20.199219 L 57.785156 37 M 59.800781 20.199219 L 76.601562 20.199219 "/>
|
|
||||||
<g style="fill:rgb(0%,0%,0%);fill-opacity:1;">
|
|
||||||
<use xlink:href="#glyph0-3" x="33" y="47"/>
|
|
||||||
</g>
|
|
||||||
<path style="fill:none;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke:rgb(0%,0%,0%);stroke-opacity:1;stroke-miterlimit:10;" d="M 140 140 L 168 140 L 168 168 L 140 168 Z M 140 140 "/>
|
|
||||||
<g style="fill:rgb(0%,0%,0%);fill-opacity:1;">
|
|
||||||
<use xlink:href="#glyph1-1" x="144" y="160"/>
|
|
||||||
<use xlink:href="#glyph1-2" x="154.671875" y="160"/>
|
|
||||||
</g>
|
|
||||||
<path style="fill:none;stroke-width:12;stroke-linecap:butt;stroke-linejoin:bevel;stroke:rgb(98.039216%,2.745098%,0%);stroke-opacity:1;stroke-miterlimit:10;" d="M 100 70 L 100 110 "/>
|
|
||||||
<path style=" stroke:none;fill-rule:nonzero;fill:rgb(98.039216%,2.745098%,0%);fill-opacity:1;" d="M 100 65 L 85 80 L 115 80 L 100 65 "/>
|
|
||||||
</g>
|
|
||||||
</svg>
|
</svg>
|
||||||
|
|
Before Width: | Height: | Size: 8 KiB After Width: | Height: | Size: 6 KiB |
|
@ -1,177 +1,42 @@
|
||||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
<!-- Public domain (CC-BY-SA if you or your laws insist), generated by Jonathan Hudson's svg_model_motors.rb -->
|
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||||
|
<svg width="100%" height="100%" viewBox="0 0 200 200" version="1.1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" xml:space="preserve" xmlns:serif="http://www.serif.com/" style="fill-rule:evenodd;clip-rule:evenodd;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:10;">
|
||||||
<svg
|
<path id="path27" d="M40,40L160,40M100,40L100,160" style="fill:none;fill-rule:nonzero;stroke:rgb(184,184,184);stroke-width:28px;"/>
|
||||||
width="200pt"
|
<path id="path29" d="M72,160C72,175.465 84.535,188 100,188C115.465,188 128,175.465 128,160C128,144.535 115.465,132 100,132C84.535,132 72,144.535 72,160M119.801,140.199L119.801,123.398M119.801,140.199L103,142.215" style="fill:none;fill-rule:nonzero;stroke:rgb(55,168,219);stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
height="200pt"
|
<g id="use31" transform="matrix(1,0,0,1,93,167)">
|
||||||
viewBox="0 0 200 200"
|
<g id="g33">
|
||||||
version="1.1"
|
<g id="use311" serif:id="use31">
|
||||||
id="svg60"
|
<path id="path5" d="M2.68,-13.863L2.68,-15.75C4.457,-15.922 5.695,-16.211 6.398,-16.617C7.102,-17.023 7.625,-17.984 7.969,-19.496L9.914,-19.496L9.914,0L7.289,0L7.289,-13.863L2.68,-13.863Z" style="fill-rule:nonzero;"/>
|
||||||
sodipodi:docname="tri_reverse.svg"
|
</g>
|
||||||
inkscape:version="1.1 (c68e22c387, 2021-05-23)"
|
</g>
|
||||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
|
||||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
|
||||||
xmlns:xlink="http://www.w3.org/1999/xlink"
|
|
||||||
xmlns="http://www.w3.org/2000/svg"
|
|
||||||
xmlns:svg="http://www.w3.org/2000/svg">
|
|
||||||
<sodipodi:namedview
|
|
||||||
id="namedview62"
|
|
||||||
pagecolor="#505050"
|
|
||||||
bordercolor="#eeeeee"
|
|
||||||
borderopacity="1"
|
|
||||||
inkscape:pageshadow="0"
|
|
||||||
inkscape:pageopacity="0"
|
|
||||||
inkscape:pagecheckerboard="0"
|
|
||||||
inkscape:document-units="pt"
|
|
||||||
showgrid="false"
|
|
||||||
inkscape:zoom="3.1875"
|
|
||||||
inkscape:cx="133.33333"
|
|
||||||
inkscape:cy="108.39216"
|
|
||||||
inkscape:window-width="1920"
|
|
||||||
inkscape:window-height="1009"
|
|
||||||
inkscape:window-x="1912"
|
|
||||||
inkscape:window-y="-8"
|
|
||||||
inkscape:window-maximized="1"
|
|
||||||
inkscape:current-layer="svg60" />
|
|
||||||
<defs
|
|
||||||
id="defs25">
|
|
||||||
<g
|
|
||||||
id="g23">
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph0-0">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d=""
|
|
||||||
id="path2" />
|
|
||||||
</symbol>
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph0-1">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d="M 2.679688 -13.863281 L 2.679688 -15.75 C 4.457031 -15.921875 5.695312 -16.210938 6.398438 -16.617188 C 7.101562 -17.023438 7.625 -17.984375 7.96875 -19.496094 L 9.914062 -19.496094 L 9.914062 0 L 7.289062 0 L 7.289062 -13.863281 Z M 2.679688 -13.863281 "
|
|
||||||
id="path5" />
|
|
||||||
</symbol>
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph0-2">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d="M 1.921875 -4.402344 C 2.527344 -5.652344 3.710938 -6.785156 5.46875 -7.804688 L 8.09375 -9.324219 C 9.269531 -10.007812 10.09375 -10.589844 10.570312 -11.074219 C 11.316406 -11.832031 11.6875 -12.695312 11.6875 -13.671875 C 11.6875 -14.8125 11.347656 -15.714844 10.664062 -16.386719 C 9.980469 -17.054688 9.070312 -17.390625 7.929688 -17.390625 C 6.242188 -17.390625 5.078125 -16.753906 4.429688 -15.476562 C 4.082031 -14.792969 3.890625 -13.84375 3.855469 -12.632812 L 1.351562 -12.632812 C 1.378906 -14.335938 1.695312 -15.726562 2.296875 -16.804688 C 3.363281 -18.699219 5.246094 -19.648438 7.945312 -19.648438 C 10.1875 -19.648438 11.824219 -19.039062 12.859375 -17.828125 C 13.894531 -16.617188 14.410156 -15.265625 14.410156 -13.78125 C 14.410156 -12.214844 13.859375 -10.875 12.757812 -9.761719 C 12.117188 -9.113281 10.972656 -8.332031 9.324219 -7.410156 L 7.453125 -6.371094 C 6.558594 -5.878906 5.855469 -5.410156 5.34375 -4.960938 C 4.433594 -4.167969 3.859375 -3.289062 3.625 -2.324219 L 14.3125 -2.324219 L 14.3125 0 L 0.875 0 C 0.964844 -1.6875 1.316406 -3.152344 1.921875 -4.402344 Z M 1.921875 -4.402344 "
|
|
||||||
id="path8" />
|
|
||||||
</symbol>
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph0-3">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d="M 2.234375 -1.375 C 1.191406 -2.644531 0.671875 -4.191406 0.671875 -6.015625 L 3.242188 -6.015625 C 3.351562 -4.75 3.585938 -3.828125 3.953125 -3.253906 C 4.589844 -2.222656 5.742188 -1.710938 7.410156 -1.710938 C 8.703125 -1.710938 9.742188 -2.054688 10.527344 -2.75 C 11.3125 -3.441406 11.703125 -4.335938 11.703125 -5.429688 C 11.703125 -6.777344 11.289062 -7.71875 10.464844 -8.257812 C 9.640625 -8.796875 8.496094 -9.0625 7.027344 -9.0625 C 6.863281 -9.0625 6.695312 -9.0625 6.527344 -9.058594 C 6.359375 -9.054688 6.1875 -9.046875 6.015625 -9.039062 L 6.015625 -11.210938 C 6.269531 -11.183594 6.484375 -11.164062 6.65625 -11.15625 C 6.832031 -11.148438 7.019531 -11.140625 7.21875 -11.140625 C 8.140625 -11.140625 8.894531 -11.289062 9.488281 -11.578125 C 10.527344 -12.089844 11.046875 -13 11.046875 -14.3125 C 11.046875 -15.289062 10.699219 -16.042969 10.007812 -16.570312 C 9.316406 -17.097656 8.507812 -17.363281 7.585938 -17.363281 C 5.945312 -17.363281 4.8125 -16.816406 4.183594 -15.722656 C 3.835938 -15.121094 3.640625 -14.265625 3.59375 -13.152344 L 1.164062 -13.152344 C 1.164062 -14.609375 1.453125 -15.851562 2.039062 -16.871094 C 3.039062 -18.695312 4.804688 -19.605469 7.328125 -19.605469 C 9.324219 -19.605469 10.867188 -19.160156 11.960938 -18.273438 C 13.054688 -17.382812 13.601562 -16.097656 13.601562 -14.410156 C 13.601562 -13.207031 13.28125 -12.230469 12.632812 -11.484375 C 12.230469 -11.019531 11.710938 -10.65625 11.074219 -10.390625 C 12.105469 -10.109375 12.910156 -9.5625 13.488281 -8.757812 C 14.066406 -7.949219 14.355469 -6.964844 14.355469 -5.796875 C 14.355469 -3.929688 13.742188 -2.40625 12.507812 -1.230469 C 11.277344 -0.0546875 9.535156 0.53125 7.273438 0.53125 C 4.957031 0.53125 3.277344 -0.101562 2.234375 -1.375 Z M 2.234375 -1.375 "
|
|
||||||
id="path11" />
|
|
||||||
</symbol>
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph1-0">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d=""
|
|
||||||
id="path14" />
|
|
||||||
</symbol>
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph1-1">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d="M 2.234375 -3.703125 C 2.269531 -3.050781 2.425781 -2.523438 2.695312 -2.117188 C 3.210938 -1.355469 4.121094 -0.976562 5.421875 -0.976562 C 6.003906 -0.976562 6.535156 -1.058594 7.015625 -1.226562 C 7.941406 -1.550781 8.40625 -2.128906 8.40625 -2.960938 C 8.40625 -3.585938 8.210938 -4.03125 7.820312 -4.296875 C 7.425781 -4.558594 6.804688 -4.785156 5.960938 -4.976562 L 4.40625 -5.328125 C 3.390625 -5.558594 2.671875 -5.808594 2.25 -6.085938 C 1.519531 -6.566406 1.15625 -7.28125 1.15625 -8.234375 C 1.15625 -9.265625 1.511719 -10.113281 2.226562 -10.773438 C 2.941406 -11.433594 3.949219 -11.765625 5.257812 -11.765625 C 6.460938 -11.765625 7.484375 -11.476562 8.324219 -10.894531 C 9.164062 -10.3125 9.585938 -9.386719 9.585938 -8.109375 L 8.125 -8.109375 C 8.046875 -8.722656 7.878906 -9.195312 7.625 -9.523438 C 7.152344 -10.121094 6.347656 -10.421875 5.210938 -10.421875 C 4.292969 -10.421875 3.636719 -10.230469 3.234375 -9.84375 C 2.832031 -9.457031 2.632812 -9.011719 2.632812 -8.5 C 2.632812 -7.9375 2.867188 -7.527344 3.335938 -7.265625 C 3.644531 -7.097656 4.339844 -6.890625 5.421875 -6.640625 L 7.03125 -6.273438 C 7.808594 -6.097656 8.40625 -5.855469 8.828125 -5.546875 C 9.558594 -5.011719 9.921875 -4.230469 9.921875 -3.210938 C 9.921875 -1.941406 9.460938 -1.03125 8.535156 -0.484375 C 7.609375 0.0625 6.535156 0.335938 5.3125 0.335938 C 3.886719 0.335938 2.769531 -0.0273438 1.960938 -0.757812 C 1.152344 -1.480469 0.757812 -2.464844 0.773438 -3.703125 Z M 2.234375 -3.703125 "
|
|
||||||
id="path17" />
|
|
||||||
</symbol>
|
|
||||||
<symbol
|
|
||||||
overflow="visible"
|
|
||||||
id="glyph1-2">
|
|
||||||
<path
|
|
||||||
style="stroke:none;"
|
|
||||||
d="M 1.53125 -7.921875 L 1.53125 -9 C 2.546875 -9.097656 3.253906 -9.265625 3.65625 -9.496094 C 4.058594 -9.726562 4.355469 -10.277344 4.554688 -11.140625 L 5.664062 -11.140625 L 5.664062 0 L 4.164062 0 L 4.164062 -7.921875 Z M 1.53125 -7.921875 "
|
|
||||||
id="path20" />
|
|
||||||
</symbol>
|
|
||||||
</g>
|
</g>
|
||||||
</defs>
|
<path id="path35-4" d="M132,40C132,55.465 144.535,68 160,68C175.465,68 188,55.465 188,40C188,24.535 175.465,12 160,12C144.535,12 132,24.535 132,40M179.801,20.199L179.801,3.398M179.801,20.199L163,22.215" style="fill:none;fill-rule:nonzero;stroke:rgb(55,168,219);stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
<path
|
<g id="use37" transform="matrix(1,0,0,1,153,47)">
|
||||||
style="fill:none;stroke:#b8b8b8;stroke-width:28;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:10;stroke-opacity:1"
|
<g id="g39">
|
||||||
d="m 40,40 h 120 m -60,0 v 120"
|
<g id="use371" serif:id="use37">
|
||||||
id="path27" />
|
<path id="path8" d="M1.922,-4.402C2.527,-5.652 3.711,-6.785 5.469,-7.805L8.094,-9.324C9.27,-10.008 10.094,-10.59 10.57,-11.074C11.316,-11.832 11.688,-12.695 11.688,-13.672C11.688,-14.813 11.348,-15.715 10.664,-16.387C9.98,-17.055 9.07,-17.391 7.93,-17.391C6.242,-17.391 5.078,-16.754 4.43,-15.477C4.082,-14.793 3.891,-13.844 3.855,-12.633L1.352,-12.633C1.379,-14.336 1.695,-15.727 2.297,-16.805C3.363,-18.699 5.246,-19.648 7.945,-19.648C10.188,-19.648 11.824,-19.039 12.859,-17.828C13.895,-16.617 14.41,-15.266 14.41,-13.781C14.41,-12.215 13.859,-10.875 12.758,-9.762C12.117,-9.113 10.973,-8.332 9.324,-7.41L7.453,-6.371C6.559,-5.879 5.855,-5.41 5.344,-4.961C4.434,-4.168 3.859,-3.289 3.625,-2.324L14.313,-2.324L14.313,0L0.875,0C0.965,-1.688 1.316,-3.152 1.922,-4.402Z" style="fill-rule:nonzero;"/>
|
||||||
<path
|
</g>
|
||||||
style="fill:none;stroke:#37a8db;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1"
|
</g>
|
||||||
d="m 72,160 c 0,15.46484 12.53516,28 28,28 15.46484,0 28,-12.53516 28,-28 0,-15.46484 -12.53516,-28 -28,-28 -15.46484,0 -28,12.53516 -28,28 m 47.80078,-19.80078 v -16.80078 m 0,16.80078 L 103,142.21484"
|
</g>
|
||||||
id="path29" />
|
<g id="path41-0" transform="matrix(0.00137106,0.999999,0.999999,-0.00137106,1.45802,0.54821)">
|
||||||
<g
|
<path d="M11.807,40C11.807,55.465 24.343,68 39.807,68C55.272,68 67.807,55.465 67.807,40C67.807,24.535 55.272,12 39.807,12C24.343,12 11.807,24.535 11.807,40M20.007,20.199L22.022,37M20.007,20.199L3.206,20.199" style="fill:none;fill-rule:nonzero;stroke:rgb(55,168,219);stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
style="fill:#000000;fill-opacity:1"
|
</g>
|
||||||
id="g33">
|
<g id="use43" transform="matrix(1,0,0,1,33,47)">
|
||||||
<use
|
<g id="g45">
|
||||||
xlink:href="#glyph0-1"
|
<g id="use431" serif:id="use43">
|
||||||
x="93"
|
<path id="path11" d="M2.234,-1.375C1.191,-2.645 0.672,-4.191 0.672,-6.016L3.242,-6.016C3.352,-4.75 3.586,-3.828 3.953,-3.254C4.59,-2.223 5.742,-1.711 7.41,-1.711C8.703,-1.711 9.742,-2.055 10.527,-2.75C11.313,-3.441 11.703,-4.336 11.703,-5.43C11.703,-6.777 11.289,-7.719 10.465,-8.258C9.641,-8.797 8.496,-9.063 7.027,-9.063C6.863,-9.063 6.695,-9.063 6.527,-9.059C6.359,-9.055 6.188,-9.047 6.016,-9.039L6.016,-11.211C6.27,-11.184 6.484,-11.164 6.656,-11.156C6.832,-11.148 7.02,-11.141 7.219,-11.141C8.141,-11.141 8.895,-11.289 9.488,-11.578C10.527,-12.09 11.047,-13 11.047,-14.313C11.047,-15.289 10.699,-16.043 10.008,-16.57C9.316,-17.098 8.508,-17.363 7.586,-17.363C5.945,-17.363 4.813,-16.816 4.184,-15.723C3.836,-15.121 3.641,-14.266 3.594,-13.152L1.164,-13.152C1.164,-14.609 1.453,-15.852 2.039,-16.871C3.039,-18.695 4.805,-19.605 7.328,-19.605C9.324,-19.605 10.867,-19.16 11.961,-18.273C13.055,-17.383 13.602,-16.098 13.602,-14.41C13.602,-13.207 13.281,-12.23 12.633,-11.484C12.23,-11.02 11.711,-10.656 11.074,-10.391C12.105,-10.109 12.91,-9.563 13.488,-8.758C14.066,-7.949 14.355,-6.965 14.355,-5.797C14.355,-3.93 13.742,-2.406 12.508,-1.23C11.277,-0.055 9.535,0.531 7.273,0.531C4.957,0.531 3.277,-0.102 2.234,-1.375Z" style="fill-rule:nonzero;"/>
|
||||||
y="167"
|
</g>
|
||||||
id="use31"
|
</g>
|
||||||
width="100%"
|
</g>
|
||||||
height="100%" />
|
<rect id="path47" x="140" y="140" width="28" height="28" style="fill:none;fill-rule:nonzero;stroke:black;stroke-width:3px;stroke-linecap:butt;stroke-linejoin:miter;"/>
|
||||||
</g>
|
<g id="g53">
|
||||||
<path
|
<g id="use49" transform="matrix(1,0,0,1,144,160)">
|
||||||
style="fill:none;stroke:#37a8db;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1"
|
<path id="path17" d="M2.234,-3.703C2.27,-3.051 2.426,-2.523 2.695,-2.117C3.211,-1.355 4.121,-0.977 5.422,-0.977C6.004,-0.977 6.535,-1.059 7.016,-1.227C7.941,-1.551 8.406,-2.129 8.406,-2.961C8.406,-3.586 8.211,-4.031 7.82,-4.297C7.426,-4.559 6.805,-4.785 5.961,-4.977L4.406,-5.328C3.391,-5.559 2.672,-5.809 2.25,-6.086C1.52,-6.566 1.156,-7.281 1.156,-8.234C1.156,-9.266 1.512,-10.113 2.227,-10.773C2.941,-11.434 3.949,-11.766 5.258,-11.766C6.461,-11.766 7.484,-11.477 8.324,-10.895C9.164,-10.313 9.586,-9.387 9.586,-8.109L8.125,-8.109C8.047,-8.723 7.879,-9.195 7.625,-9.523C7.152,-10.121 6.348,-10.422 5.211,-10.422C4.293,-10.422 3.637,-10.23 3.234,-9.844C2.832,-9.457 2.633,-9.012 2.633,-8.5C2.633,-7.938 2.867,-7.527 3.336,-7.266C3.645,-7.098 4.34,-6.891 5.422,-6.641L7.031,-6.273C7.809,-6.098 8.406,-5.855 8.828,-5.547C9.559,-5.012 9.922,-4.23 9.922,-3.211C9.922,-1.941 9.461,-1.031 8.535,-0.484C7.609,0.063 6.535,0.336 5.313,0.336C3.887,0.336 2.77,-0.027 1.961,-0.758C1.152,-1.48 0.758,-2.465 0.773,-3.703L2.234,-3.703Z" style="fill-rule:nonzero;"/>
|
||||||
d="m 132,40 c 0,15.464844 12.53516,28 28,28 15.46484,0 28,-12.535156 28,-28 0,-15.464844 -12.53516,-28 -28,-28 -15.46484,0 -28,12.535156 -28,28 M 179.80078,20.199219 V 3.398438 m 0,16.800781 L 163,22.214844"
|
</g>
|
||||||
id="path35-4" />
|
<g id="use51" transform="matrix(1,0,0,1,154.672,160)">
|
||||||
<g
|
<path id="path20" d="M1.531,-7.922L1.531,-9C2.547,-9.098 3.254,-9.266 3.656,-9.496C4.059,-9.727 4.355,-10.277 4.555,-11.141L5.664,-11.141L5.664,0L4.164,0L4.164,-7.922L1.531,-7.922Z" style="fill-rule:nonzero;"/>
|
||||||
style="fill:#000000;fill-opacity:1"
|
</g>
|
||||||
id="g39">
|
</g>
|
||||||
<use
|
<path id="path55" d="M100,70L100,110" style="fill:none;fill-rule:nonzero;stroke:rgb(250,5,0);stroke-width:12px;stroke-linecap:butt;stroke-linejoin:bevel;"/>
|
||||||
xlink:href="#glyph0-2"
|
<path id="path57" d="M100,65L85,80L115,80L100,65" style="fill:rgb(250,5,0);fill-rule:nonzero;"/>
|
||||||
x="153"
|
|
||||||
y="47"
|
|
||||||
id="use37"
|
|
||||||
width="100%"
|
|
||||||
height="100%" />
|
|
||||||
</g>
|
|
||||||
<path
|
|
||||||
style="fill:none;stroke:#37a8db;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1"
|
|
||||||
d="m 11.807447,40 c 0,15.464844 12.535157,28 28.000001,28 15.464844,0 28,-12.535156 28,-28 0,-15.464844 -12.535156,-28 -28,-28 C 24.342604,12 11.807447,24.535156 11.807447,40 M 20.006667,20.199219 22.022292,37 M 20.006667,20.199219 H 3.2058824"
|
|
||||||
id="path41-0" />
|
|
||||||
<g
|
|
||||||
style="fill:#000000;fill-opacity:1"
|
|
||||||
id="g45">
|
|
||||||
<use
|
|
||||||
xlink:href="#glyph0-3"
|
|
||||||
x="33"
|
|
||||||
y="47"
|
|
||||||
id="use43"
|
|
||||||
width="100%"
|
|
||||||
height="100%" />
|
|
||||||
</g>
|
|
||||||
<path
|
|
||||||
style="fill:none;stroke:#000000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:10;stroke-opacity:1"
|
|
||||||
d="m 140,140 h 28 v 28 h -28 z m 0,0"
|
|
||||||
id="path47" />
|
|
||||||
<g
|
|
||||||
style="fill:#000000;fill-opacity:1"
|
|
||||||
id="g53">
|
|
||||||
<use
|
|
||||||
xlink:href="#glyph1-1"
|
|
||||||
x="144"
|
|
||||||
y="160"
|
|
||||||
id="use49"
|
|
||||||
width="100%"
|
|
||||||
height="100%" />
|
|
||||||
<use
|
|
||||||
xlink:href="#glyph1-2"
|
|
||||||
x="154.67188"
|
|
||||||
y="160"
|
|
||||||
id="use51"
|
|
||||||
width="100%"
|
|
||||||
height="100%" />
|
|
||||||
</g>
|
|
||||||
<path
|
|
||||||
style="fill:none;stroke:#fa0500;stroke-width:12;stroke-linecap:butt;stroke-linejoin:bevel;stroke-miterlimit:10;stroke-opacity:1"
|
|
||||||
d="m 100,70 v 40"
|
|
||||||
id="path55" />
|
|
||||||
<path
|
|
||||||
style="fill:#fa0500;fill-opacity:1;fill-rule:nonzero;stroke:none"
|
|
||||||
d="M 100,65 85,80 h 30 L 100,65"
|
|
||||||
id="path57" />
|
|
||||||
</svg>
|
</svg>
|
||||||
|
|
Before Width: | Height: | Size: 9.9 KiB After Width: | Height: | Size: 6.3 KiB |
|
@ -113,7 +113,7 @@
|
||||||
| | SYM_MAH_KM_1 | SYM.MAH_KM_1 | mAh per Kilometre, right side | 108 | 0x6C |
|
| | SYM_MAH_KM_1 | SYM.MAH_KM_1 | mAh per Kilometre, right side | 108 | 0x6C |
|
||||||
|  | SYM_WH | SYM.WH | Watthours symbol | 109 | 0x6D |
|
|  | SYM_WH | SYM.WH | Watthours symbol | 109 | 0x6D |
|
||||||
|  | SYM_WH_KM | SYM.WH_KM | Watthours per Kilometre | 110 | 0x6E |
|
|  | SYM_WH_KM | SYM.WH_KM | Watthours per Kilometre | 110 | 0x6E |
|
||||||
|  | SYM_WH_MI | SYM.WH_MI | Watthours per Mile | 111 | 0x6F |
|
|  | SYM_WH_MI | SYM.WH_MI | Watthours per Mile | 111 | 0x6F |
|
||||||
|  | SYM_WH_NM | SYM.WH_NM | Watthours per Nautical Mile | 112 | 0x70 |
|
|  | SYM_WH_NM | SYM.WH_NM | Watthours per Nautical Mile | 112 | 0x70 |
|
||||||
|  | SYM_WATT | SYM.WATT | Watts symbol | 113 | 0x71 |
|
|  | SYM_WATT | SYM.WATT | Watts symbol | 113 | 0x71 |
|
||||||
|  | SYM_MW | SYM.MW | Milliwatts symbol | 114 | 0x72 |
|
|  | SYM_MW | SYM.MW | Milliwatts symbol | 114 | 0x72 |
|
||||||
|
@ -224,6 +224,7 @@
|
||||||
|  | SYM_FLIGHT_MINS_REMAINING | SYM.FLIGHT_MINS_REMAINING | Flight time (mins) remaining | 218 | 0xDA |
|
|  | SYM_FLIGHT_MINS_REMAINING | SYM.FLIGHT_MINS_REMAINING | Flight time (mins) remaining | 218 | 0xDA |
|
||||||
|  | SYM_FLIGHT_HOURS_REMAINING | | Flight time (hours) remaining | 219 | 0xDB |
|
|  | SYM_FLIGHT_HOURS_REMAINING | | Flight time (hours) remaining | 219 | 0xDB |
|
||||||
|  | SYM_GROUND_COURSE | SYM.GROUND_COURSE | Ground course | 220 | 0xDC |
|
|  | SYM_GROUND_COURSE | SYM.GROUND_COURSE | Ground course | 220 | 0xDC |
|
||||||
|
|  | SYM_ALERT | SYM.ALERT | General Alert | 221 | 0xDD |
|
||||||
|  | SYM_TERRAIN_FOLLOWING | SYM.TERRAIN_FOLLOWING | Terrain following | 251 | 0xFB |
|
|  | SYM_TERRAIN_FOLLOWING | SYM.TERRAIN_FOLLOWING | Terrain following | 251 | 0xFB |
|
||||||
|  | SYM_CROSS_TRACK_ERROR | SYM.CROSS_TRACK_ERROR | Cross track error | 252 | 0xFC |
|
|  | SYM_CROSS_TRACK_ERROR | SYM.CROSS_TRACK_ERROR | Cross track error | 252 | 0xFC |
|
||||||
|  | SYM_ADSB | SYM.ADSB | ADSB | 253 | 0xFD |
|
|  | SYM_ADSB | SYM.ADSB | ADSB | 253 | 0xFD |
|
||||||
|
@ -284,6 +285,7 @@
|
||||||
|  | SYM_HOME_DIST | | Home distance icon | 357 | 0x165 |
|
|  | SYM_HOME_DIST | | Home distance icon | 357 | 0x165 |
|
||||||
|  | SYM_AH_CH_CENTER | SYM.AH_CROSSHAIRS | Default crosshair centre | 358 | 0x166 |
|
|  | SYM_AH_CH_CENTER | SYM.AH_CROSSHAIRS | Default crosshair centre | 358 | 0x166 |
|
||||||
|  | SYM_FLIGHT_DIST_REMAINING | SYM.FLIGHT_DIST_REMAINING | Flight distance remaining | 359 | 0x167 |
|
|  | SYM_FLIGHT_DIST_REMAINING | SYM.FLIGHT_DIST_REMAINING | Flight distance remaining | 359 | 0x167 |
|
||||||
|
|  | SYM_ODOMETER | SYM.ODOMETER | Odometer (total aircraft distance) | 360 | 0x168 |
|
||||||
|  | SYM_AH_CH_TYPE3 | SYM.AH_CROSSHAIRS | Crosshair type 3 | 400 - 402 | 0x190 - 0x192 |
|
|  | SYM_AH_CH_TYPE3 | SYM.AH_CROSSHAIRS | Crosshair type 3 | 400 - 402 | 0x190 - 0x192 |
|
||||||
|  | SYM_AH_CH_TYPE4 | SYM.AH_CROSSHAIRS | Crosshair type 4 | 403 - 405 | 0x193 - 0x195 |
|
|  | SYM_AH_CH_TYPE4 | SYM.AH_CROSSHAIRS | Crosshair type 4 | 403 - 405 | 0x193 - 0x195 |
|
||||||
|  | SYM_AH_CH_TYPE5 | SYM.AH_CROSSHAIRS | Crosshair type 5 | 406 - 408 | 0x196 - 0x198 |
|
|  | SYM_AH_CH_TYPE5 | SYM.AH_CROSSHAIRS | Crosshair type 5 | 406 - 408 | 0x196 - 0x198 |
|
||||||
|
@ -322,5 +324,7 @@
|
||||||
|  | SYM_SERVO_PAN_IS_CENTRED | | Pan servo is centred | 454 | 0x1C6 |
|
|  | SYM_SERVO_PAN_IS_CENTRED | | Pan servo is centred | 454 | 0x1C6 |
|
||||||
|  | SYM_SERVO_PAN_IS_OFFSET_L | SYM.PAN_SERVO_IS_OFFSET_L | Pan servo is moved to the left | 455 | 0x1C7 |
|
|  | SYM_SERVO_PAN_IS_OFFSET_L | SYM.PAN_SERVO_IS_OFFSET_L | Pan servo is moved to the left | 455 | 0x1C7 |
|
||||||
|  | SYM_SERVO_PAN_IS_OFFSET_R | | Pan servo is moved to the right | 456 | 0x1C8 |
|
|  | SYM_SERVO_PAN_IS_OFFSET_R | | Pan servo is moved to the right | 456 | 0x1C8 |
|
||||||
|
|  | SYM_PILOT_LOGO_SML_L | SYM.PILOT_LOGO_SML_L | Small Pilot logo | 469 - 471 | 0x1D5 - 0x1D7 |
|
||||||
|
|  | SYM_PILOT_LOGO_LRG_START | | Large Pilot logo | 472 - 511 | 0x1D5 - 0x1D7 |
|
||||||
|
|
||||||
_*_ Do not change the IDs of these characters
|
_*_ Do not change the IDs of these characters
|
||||||
|
|
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 15 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 15 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 15 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
BIN
resources/osd/analogue/default/221.png
Normal file
After Width: | Height: | Size: 199 B |
Before Width: | Height: | Size: 249 B After Width: | Height: | Size: 252 B |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
BIN
resources/osd/analogue/default/360.png
Normal file
After Width: | Height: | Size: 2 KiB |
BIN
resources/osd/analogue/default/469_471.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
BIN
resources/osd/analogue/default/472_511.png
Normal file
After Width: | Height: | Size: 3 KiB |
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 14 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
Before Width: | Height: | Size: 14 KiB After Width: | Height: | Size: 14 KiB |
Before Width: | Height: | Size: 1.7 KiB After Width: | Height: | Size: 2.2 KiB |
BIN
resources/osd/digital/default/12x18/221.png
Normal file
After Width: | Height: | Size: 1.5 KiB |
BIN
resources/osd/digital/default/12x18/360.png
Normal file
After Width: | Height: | Size: 2 KiB |
BIN
resources/osd/digital/default/12x18/469_471.png
Normal file
After Width: | Height: | Size: 2.3 KiB |
BIN
resources/osd/digital/default/12x18/472_511.png
Normal file
After Width: | Height: | Size: 8.7 KiB |
BIN
resources/osd/digital/default/24x36/221.png
Normal file
After Width: | Height: | Size: 2.4 KiB |
BIN
resources/osd/digital/default/24x36/360.png
Normal file
After Width: | Height: | Size: 2.1 KiB |
BIN
resources/osd/digital/default/24x36/469_471.png
Normal file
After Width: | Height: | Size: 3.1 KiB |
BIN
resources/osd/digital/default/24x36/472_511.png
Normal file
After Width: | Height: | Size: 16 KiB |
BIN
resources/osd/digital/default/36x54/221.png
Normal file
After Width: | Height: | Size: 2.6 KiB |
BIN
resources/osd/digital/default/36x54/360.png
Normal file
After Width: | Height: | Size: 2.5 KiB |
BIN
resources/osd/digital/default/36x54/469_471.png
Normal file
After Width: | Height: | Size: 3.4 KiB |
BIN
resources/osd/digital/default/36x54/472_511.png
Normal file
After Width: | Height: | Size: 20 KiB |
32
src/css/tabs/ez_tune.css
Normal file
|
@ -0,0 +1,32 @@
|
||||||
|
.ez-tune-preview {
|
||||||
|
background-color: #8ecae6;
|
||||||
|
margin-left: 1em;
|
||||||
|
margin-bottom: 1em;
|
||||||
|
min-width: 25%;
|
||||||
|
padding: 0.5em;
|
||||||
|
}
|
||||||
|
|
||||||
|
.ez-tune-preview h2 {
|
||||||
|
font-size: 1.3em;
|
||||||
|
margin-bottom: 1em;
|
||||||
|
margin-top: 0.5em;
|
||||||
|
color: #303030
|
||||||
|
}
|
||||||
|
|
||||||
|
.ez-tune-preview table {
|
||||||
|
width: 100%;
|
||||||
|
}
|
||||||
|
|
||||||
|
.ez-tune-preview table td,
|
||||||
|
.ez-tune-preview table th {
|
||||||
|
padding: 0.5em;
|
||||||
|
text-align: center;
|
||||||
|
}
|
||||||
|
|
||||||
|
.ez-tune-preview table th {
|
||||||
|
background-color: #3EA5D4;
|
||||||
|
}
|
||||||
|
|
||||||
|
.ez-tune-preview table td {
|
||||||
|
background-color: #A8D6EC;
|
||||||
|
}
|
|
@ -136,8 +136,9 @@
|
||||||
|
|
||||||
.tab-magnetometer #interactive_block {
|
.tab-magnetometer #interactive_block {
|
||||||
position: absolute;
|
position: absolute;
|
||||||
width: calc(100% - 40px);
|
width: calc(100% - 655px);
|
||||||
height: calc(100% - 245px);
|
height: 771px;
|
||||||
|
min-height: calc(100% - 200px);
|
||||||
background-color: #f9f9f9;
|
background-color: #f9f9f9;
|
||||||
border-radius: 5px;
|
border-radius: 5px;
|
||||||
border: 1px solid #e4e4e4;
|
border: 1px solid #e4e4e4;
|
||||||
|
@ -190,6 +191,17 @@ progress[value]::-webkit-progress-value {
|
||||||
box-shadow: 0 0 3px rgba(0, 0, 0, 0.25) inset;
|
box-shadow: 0 0 3px rgba(0, 0, 0, 0.25) inset;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.tab-magnetometer-left-wrapper {
|
||||||
|
float:left;
|
||||||
|
width: calc( 100% - 655px );
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-magnetometer-right-wrapper {
|
||||||
|
float:right;
|
||||||
|
width: 600px;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
@media only screen and (max-width: 1055px) , only screen and (max-device-width: 1055px) {
|
@media only screen and (max-width: 1055px) , only screen and (max-device-width: 1055px) {
|
||||||
|
|
||||||
#magnetometer-map {
|
#magnetometer-map {
|
||||||
|
|
|
@ -401,18 +401,21 @@
|
||||||
/* background: #D6D6D6 linear-gradient(-45deg, rgba(255, 255, 255, .2) 10%, transparent 10%, transparent 20%, rgba(255, 255, 255, .2) 20%, rgba(255, 255, 255, .2) 30%, transparent 30%, transparent 40%, rgba(255, 255, 255, .2) 40%, rgba(255, 255, 255, .2) 50%, transparent 50%, transparent 60%, rgba(255, 255, 255, .2) 60%, rgba(255, 255, 255, .2) 70%, transparent 70%, transparent 80%, rgba(255, 255, 255, .2) 80%, rgba(255, 255, 255, .2) 90%, transparent 90%, transparent 100%, rgba(255, 255, 255, .2) 100%, transparent); */
|
/* background: #D6D6D6 linear-gradient(-45deg, rgba(255, 255, 255, .2) 10%, transparent 10%, transparent 20%, rgba(255, 255, 255, .2) 20%, rgba(255, 255, 255, .2) 30%, transparent 30%, transparent 40%, rgba(255, 255, 255, .2) 40%, rgba(255, 255, 255, .2) 50%, transparent 50%, transparent 60%, rgba(255, 255, 255, .2) 60%, rgba(255, 255, 255, .2) 70%, transparent 70%, transparent 80%, rgba(255, 255, 255, .2) 80%, rgba(255, 255, 255, .2) 90%, transparent 90%, transparent 100%, rgba(255, 255, 255, .2) 100%, transparent); */
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-slider-row {
|
.pid-slider-row,
|
||||||
|
.pid-switch-row {
|
||||||
display: flex;
|
display: flex;
|
||||||
padding: 4px;
|
padding: 4px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-slider-row span {
|
.pid-slider-row span,
|
||||||
|
.pid-switch-row .label {
|
||||||
margin-right: 2em;
|
margin-right: 2em;
|
||||||
width: 120px;
|
width: 120px;
|
||||||
line-height: 22px;;
|
line-height: 22px;;
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-slider-row input[type="number"] {
|
.pid-slider-row input[type="number"],
|
||||||
|
.pid-switch-row input[type="number"] {
|
||||||
font-family: 'open_sansregular', 'Segoe UI', Tahoma, sans-serif;
|
font-family: 'open_sansregular', 'Segoe UI', Tahoma, sans-serif;
|
||||||
background-color: #fff;
|
background-color: #fff;
|
||||||
border: 1px solid #ccc;
|
border: 1px solid #ccc;
|
||||||
|
@ -422,7 +425,9 @@
|
||||||
margin-right: 2em;
|
margin-right: 2em;
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-slider-row input[type="range"] {
|
.pid-slider-row input[type="range"],
|
||||||
|
.pid-switch-row input[type="range"]
|
||||||
|
{
|
||||||
display: block;
|
display: block;
|
||||||
flex-grow: 100;
|
flex-grow: 100;
|
||||||
}
|
}
|
||||||
|
@ -436,16 +441,26 @@
|
||||||
padding: 4px;
|
padding: 4px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-sliders-axis[data-axis="roll"] {
|
.pid-sliders-axis[data-axis="roll"],
|
||||||
background-color: #afe4fe;
|
.pid-sliders-axis[data-axis="0"] {
|
||||||
|
background-color: #8ecae6;
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-sliders-axis[data-axis="pitch"] {
|
.pid-sliders-axis[data-axis="pitch"],
|
||||||
background-color: #C4B5FF;
|
.pid-sliders-axis[data-axis="1"]
|
||||||
|
{
|
||||||
|
background-color: #00b4d8;
|
||||||
}
|
}
|
||||||
|
|
||||||
.pid-sliders-axis[data-axis="yaw"] {
|
.pid-sliders-axis[data-axis="yaw"],
|
||||||
background-color: #E6B6F0;
|
.pid-sliders-axis[data-axis="2"]
|
||||||
|
{
|
||||||
|
background-color: #e9c46a;
|
||||||
|
}
|
||||||
|
|
||||||
|
.pid-sliders-axis[data-axis="3"]
|
||||||
|
{
|
||||||
|
background-color: #f4a261;
|
||||||
}
|
}
|
||||||
|
|
||||||
#pid-sliders {
|
#pid-sliders {
|
||||||
|
|
|
@ -40,6 +40,21 @@
|
||||||
float: left;
|
float: left;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.attitude_note1 {
|
||||||
|
position: absolute;
|
||||||
|
left: 130px;
|
||||||
|
top: 29px;
|
||||||
|
font-size: 10px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.attitude_note2 {
|
||||||
|
position: absolute;
|
||||||
|
left: 130px;
|
||||||
|
top: 13px;
|
||||||
|
font-size: 10px;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
#interactive_block a.reset {
|
#interactive_block a.reset {
|
||||||
position: absolute;
|
position: absolute;
|
||||||
display: block;
|
display: block;
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
<div class="tab-configuration tab-advanced-tuning toolbar_fixed_bottom">
|
<div class="tab-configuration tab-advanced-tuning toolbar_fixed_bottom">
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="tab_title"><span data-i18n="tabAdvancedTuningTitle">Advanced Tuning</span><span class="airplaneTuningTitle">: Fixed Wing</span><span class="multirotorTuningTitle">: Multirotors</span></div>
|
<div class="tab_title"><span data-i18n="tabAdvancedTuningTitle"></span><span class="airplaneTuningTitle" data-i18n="tabAdvancedTuningAirplaneTuningTitle"></span><span class="multirotorTuningTitle" data-i18n="tabAdvancedTuningMultirotorTuningTitle"></span></div>
|
||||||
|
|
||||||
<!-- Airplane Advanced Tuning-->
|
<!-- Airplane Advanced Tuning-->
|
||||||
<div class="airplaneTuning">
|
<div class="airplaneTuning">
|
||||||
|
@ -139,7 +139,8 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
</div> <!-- left wrapper -->
|
</div>
|
||||||
|
<!-- left wrapper -->
|
||||||
|
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
<div class="config-section gui_box grey">
|
<div class="config-section gui_box grey">
|
||||||
|
@ -163,7 +164,7 @@
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<input type="checkbox" class="toggle update_preview" id="cruiseManualThrottle" data-setting="nav_fw_allow_manual_thr_increase" data-live="true" />
|
<input type="checkbox" class="toggle update_preview" id="cruiseManualThrottle" data-setting="nav_fw_allow_manual_thr_increase" data-live="true" />
|
||||||
<label for="cruiseManualThrottle"><span data-i18n="cruiseManualThrottleLabel"></span></label>
|
<label for="cruiseManualThrottle"><span data-i18n="cruiseManualThrottleLabel"></span></label>
|
||||||
<div for="cruiseManualThrottle" class="helpicon cf_tip" data-i18n_title="cruiseManualThrottleHelp"></div>
|
<div for="cruiseManualThrottle" class="helpicon cf_tip" data-i18n_title="cruiseManualThrottleHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -234,7 +235,7 @@
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<input type="checkbox" class="toggle update_preview" id="soarMotorStop" data-setting="nav_fw_soaring_motor_stop" data-live="true" />
|
<input type="checkbox" class="toggle update_preview" id="soarMotorStop" data-setting="nav_fw_soaring_motor_stop" data-live="true" />
|
||||||
<label for="soarMotorStop"><span data-i18n="soarMotorStop"></span></label>
|
<label for="soarMotorStop"><span data-i18n="soarMotorStop"></span></label>
|
||||||
<div for="soarMotorStop" class="helpicon cf_tip" data-i18n_title="soarMotorStopHelp"></div>
|
<div for="soarMotorStop" class="helpicon cf_tip" data-i18n_title="soarMotorStopHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -247,10 +248,12 @@
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div> <!-- right wrapper -->
|
</div>
|
||||||
|
<!-- right wrapper -->
|
||||||
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
</div> <!-- Airplane Advanced Tuning -->
|
</div>
|
||||||
|
<!-- Airplane Advanced Tuning -->
|
||||||
|
|
||||||
<!-- Multirotor Advanced tuning -->
|
<!-- Multirotor Advanced tuning -->
|
||||||
<div class="multirotorTuning">
|
<div class="multirotorTuning">
|
||||||
|
@ -298,7 +301,8 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div> <!-- left wrapper -->
|
</div>
|
||||||
|
<!-- left wrapper -->
|
||||||
|
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
<div class="config-section gui_box grey">
|
<div class="config-section gui_box grey">
|
||||||
|
@ -338,7 +342,7 @@
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="brakingBoostSpeedThreshold" type="number" data-unit="cms"data-setting="nav_mc_braking_boost_speed_threshold" data-setting-multiplier="1" step="1" min="100" max="1000" />
|
<input id="brakingBoostSpeedThreshold" type="number" data-unit="cms" data-setting="nav_mc_braking_boost_speed_threshold" data-setting-multiplier="1" step="1" min="100" max="1000" />
|
||||||
<label for="brakingBoostSpeedThreshold"><span data-i18n="brakingBoostSpeedThreshold"></span></label>
|
<label for="brakingBoostSpeedThreshold"><span data-i18n="brakingBoostSpeedThreshold"></span></label>
|
||||||
<div for="brakingBoostSpeedThreshold" class="helpicon cf_tip" data-i18n_title="brakingBoostSpeedThresholdTip"></div>
|
<div for="brakingBoostSpeedThreshold" class="helpicon cf_tip" data-i18n_title="brakingBoostSpeedThresholdTip"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -357,10 +361,12 @@
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div> <!-- right wrapper -->
|
</div>
|
||||||
|
<!-- right wrapper -->
|
||||||
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
</div> <!-- Multirotor Advanced Tuning -->
|
</div>
|
||||||
|
<!-- Multirotor Advanced Tuning -->
|
||||||
|
|
||||||
<!-- Common tuning -->
|
<!-- Common tuning -->
|
||||||
<div class="tab_subtitle" data-i18n="tabAdvancedTuningGenericTitle">Advanced Tuning: Generic settings</div>
|
<div class="tab_subtitle" data-i18n="tabAdvancedTuningGenericTitle">Advanced Tuning: Generic settings</div>
|
||||||
|
@ -384,7 +390,7 @@
|
||||||
<div for="rthAltitude" class="helpicon cf_tip" data-i18n_title="rthAltitudeHelp"></div>
|
<div for="rthAltitude" class="helpicon cf_tip" data-i18n_title="rthAltitudeHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="rthHomeAltitude" data-unit="cm" data-setting="nav_rth_home_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
<input type="number" id="rthHomeAltitude" data-unit="cm" data-setting="nav_rth_home_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
<label for="rthHomeAltitude"><span data-i18n="rthHomeAltitudeLabel"></span></label>
|
<label for="rthHomeAltitude"><span data-i18n="rthHomeAltitudeLabel"></span></label>
|
||||||
<div for="rthHomeAltitude" class="helpicon cf_tip" data-i18n_title="rthHomeAltitudeHelp"></div>
|
<div for="rthHomeAltitude" class="helpicon cf_tip" data-i18n_title="rthHomeAltitudeHelp"></div>
|
||||||
|
@ -408,6 +414,18 @@
|
||||||
<div for="rthTwoStageAlt" class="helpicon cf_tip" data-i18n_title="rthTwoStageAltHelp"></div>
|
<div for="rthTwoStageAlt" class="helpicon cf_tip" data-i18n_title="rthTwoStageAltHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" id="rthUseLinearDescent" data-setting="nav_rth_use_linear_descent" data-live="true" />
|
||||||
|
<label for="rthUseLinearDescent"><span data-i18n="rthUseLinearDescent"></span></label>
|
||||||
|
<div for="rthUseLinearDescent" class="helpicon cf_tip" data-i18n_title="rthUseLinearDescentHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="rthLinearDescentStart" data-unit="m" data-setting="nav_rth_linear_descent_start_distance" data-setting-multiplier="1" step="1" min="0" max="10000" />
|
||||||
|
<label for="rthLinearDescentStart"><span data-i18n="rthLinearDescentStart"></span></label>
|
||||||
|
<div for="rthLinearDescentStart" class="helpicon cf_tip" data-i18n_title="rthLinearDescentStartHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<input type="checkbox" class="toggle update_preview" id="rthClimbIgnoreEmergency" data-setting="nav_rth_climb_ignore_emerg" data-live="true" />
|
<input type="checkbox" class="toggle update_preview" id="rthClimbIgnoreEmergency" data-setting="nav_rth_climb_ignore_emerg" data-live="true" />
|
||||||
<label for="rthClimbIgnoreEmergency"><span data-i18n="rthClimbIgnoreEmergency"></span></label>
|
<label for="rthClimbIgnoreEmergency"><span data-i18n="rthClimbIgnoreEmergency"></span></label>
|
||||||
|
@ -470,17 +488,18 @@
|
||||||
<label for="fsMissionDelay"><span data-i18n="fsMissionDelay"></span></label>
|
<label for="fsMissionDelay"><span data-i18n="fsMissionDelay"></span></label>
|
||||||
<div for="fsMissionDelay" class="helpicon cf_tip" data-i18n_title="fsMissionDelayHelp"></div>
|
<div for="fsMissionDelay" class="helpicon cf_tip" data-i18n_title="fsMissionDelayHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<!--
|
<!--
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<input type="checkbox" class="toggle update_preview" id="drNavigation" data-setting="inav_allow_dead_reckoning" data-live="true" />
|
<input type="checkbox" class="toggle update_preview" id="drNavigation" data-setting="inav_allow_dead_reckoning" data-live="true" />
|
||||||
<label for="drNavigation"><span data-i18n="drNavigation"></span></label>
|
<label for="drNavigation"><span data-i18n="drNavigation"></span></label>
|
||||||
<div for="drNavigation" class="helpicon cf_tip" data-i18n_title="drNavigationHelp"></div>
|
<div for="drNavigation" class="helpicon cf_tip" data-i18n_title="drNavigationHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
-->
|
-->
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
</div> <!-- Left wrapper -->
|
</div>
|
||||||
|
<!-- Left wrapper -->
|
||||||
|
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
|
|
||||||
|
@ -500,13 +519,13 @@
|
||||||
<label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
|
<label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
|
||||||
<div for="navAutoClimbRate" class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
|
<div for="navAutoClimbRate" class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="navMaxAltitude" data-unit="cm" data-setting="nav_max_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
<input type="number" id="navMaxAltitude" data-unit="cm" data-setting="nav_max_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
<label for="navMaxAltitude"><span data-i18n="navMaxAltitude"></span></label>
|
<label for="navMaxAltitude"><span data-i18n="navMaxAltitude"></span></label>
|
||||||
<div for="navMaxAltitude" class="helpicon cf_tip" data-i18n_title="navMaxAltitudeHelp"></div>
|
<div for="navMaxAltitude" class="helpicon cf_tip" data-i18n_title="navMaxAltitudeHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="select">
|
<div class="select">
|
||||||
<select id="navMotorStop" data-setting="nav_overrides_motor_stop"></select>
|
<select id="navMotorStop" data-setting="nav_overrides_motor_stop"></select>
|
||||||
<label for="navMotorStop"><span data-i18n="navMotorStop"></span></label>
|
<label for="navMotorStop"><span data-i18n="navMotorStop"></span></label>
|
||||||
|
@ -545,7 +564,7 @@
|
||||||
<label for="wpEnforceAlt"><span data-i18n="wpEnforceAlt"></span></label>
|
<label for="wpEnforceAlt"><span data-i18n="wpEnforceAlt"></span></label>
|
||||||
<div for="wpEnforceAlt" class="helpicon cf_tip" data-i18n_title="wpEnforceAltHelp"></div>
|
<div for="wpEnforceAlt" class="helpicon cf_tip" data-i18n_title="wpEnforceAltHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="wpTrackingAccuracy" data-setting="nav_fw_wp_tracking_accuracy" data-setting-multiplier="1" step="1" min="0" max="10" />
|
<input type="number" id="wpTrackingAccuracy" data-setting="nav_fw_wp_tracking_accuracy" data-setting-multiplier="1" step="1" min="0" max="10" />
|
||||||
<label for="wpTrackingAccuracy"><span data-i18n="wpTrackingAccuracy"></span></label>
|
<label for="wpTrackingAccuracy"><span data-i18n="wpTrackingAccuracy"></span></label>
|
||||||
|
@ -557,7 +576,7 @@
|
||||||
<label for="wpTrackingAngle"><span data-i18n="wpTrackingAngle"></span></label>
|
<label for="wpTrackingAngle"><span data-i18n="wpTrackingAngle"></span></label>
|
||||||
<div for="wpTrackingAngle" class="helpicon cf_tip" data-i18n_title="wpTrackingAngleHelp"></div>
|
<div for="wpTrackingAngle" class="helpicon cf_tip" data-i18n_title="wpTrackingAngleHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="select">
|
<div class="select">
|
||||||
<select id="wpTurnSmoothing" data-setting="nav_fw_wp_turn_smoothing"></select>
|
<select id="wpTurnSmoothing" data-setting="nav_fw_wp_turn_smoothing"></select>
|
||||||
<label for="wpTurnSmoothing"><span data-i18n="wpTurnSmoothing"></span></label>
|
<label for="wpTurnSmoothing"><span data-i18n="wpTurnSmoothing"></span></label>
|
||||||
|
@ -604,9 +623,11 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
</div> <!-- Right wrapper -->
|
</div>
|
||||||
|
<!-- Right wrapper -->
|
||||||
|
|
||||||
</div> <!-- Common tuning -->
|
</div>
|
||||||
|
<!-- Common tuning -->
|
||||||
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
|
@ -617,4 +638,4 @@
|
||||||
<a id="advanced-tuning-save-button" class="save" href="#" data-i18n="advancedTuningSave"></a>
|
<a id="advanced-tuning-save-button" class="save" href="#" data-i18n="advancedTuningSave"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
|
@ -38,6 +38,27 @@ TABS.advanced_tuning.initialize = function (callback) {
|
||||||
|
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
|
// Set up required field warnings
|
||||||
|
$('#launchIdleThr').keyup(function() {
|
||||||
|
TABS.advanced_tuning.checkRequirements_IdleThrottle();
|
||||||
|
});
|
||||||
|
|
||||||
|
$('#launchIdleDelay').keyup(function() {
|
||||||
|
TABS.advanced_tuning.checkRequirements_IdleThrottle();
|
||||||
|
});
|
||||||
|
|
||||||
|
$('#rthHomeAltitude').keyup(function() {
|
||||||
|
TABS.advanced_tuning.checkRequirements_LinearDescent();
|
||||||
|
});
|
||||||
|
|
||||||
|
$('#rthUseLinearDescent').change(function() {
|
||||||
|
TABS.advanced_tuning.checkRequirements_LinearDescent();
|
||||||
|
});
|
||||||
|
|
||||||
|
// Preload required field warnings
|
||||||
|
TABS.advanced_tuning.checkRequirements_IdleThrottle();
|
||||||
|
TABS.advanced_tuning.checkRequirements_LinearDescent();
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
Settings.saveInputs().then(function () {
|
Settings.saveInputs().then(function () {
|
||||||
var self = this;
|
var self = this;
|
||||||
|
@ -68,8 +89,28 @@ TABS.advanced_tuning.initialize = function (callback) {
|
||||||
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
GUI.handleReconnect($('.tab_advanced_tuning a'));
|
GUI.handleReconnect($('.tab_advanced_tuning a'));
|
||||||
}
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
$incLD = 0;
|
||||||
|
|
||||||
|
TABS.advanced_tuning.checkRequirements_IdleThrottle = function() {
|
||||||
|
let idleThrottle = $('#launchIdleThr');
|
||||||
|
if ($('#launchIdleDelay').val() > 0 && (idleThrottle.val() == "" || idleThrottle.val() < "1150")) {
|
||||||
|
idleThrottle.addClass('inputRequiredWarning');
|
||||||
|
} else {
|
||||||
|
idleThrottle.removeClass('inputRequiredWarning');
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
TABS.advanced_tuning.checkRequirements_LinearDescent = function() {
|
||||||
|
let rthHomeAlt = $('#rthHomeAltitude');
|
||||||
|
let minRthHomeAlt = 1000.0 / rthHomeAlt.data('setting-multiplier'); // 10 metres minimum recommended for safety.
|
||||||
|
|
||||||
|
if ($('#rthUseLinearDescent').is(":checked") && (rthHomeAlt.val() == "" || parseFloat(rthHomeAlt.val()) < minRthHomeAlt)) {
|
||||||
|
rthHomeAlt.addClass('inputRequiredWarning');
|
||||||
|
} else {
|
||||||
|
rthHomeAlt.removeClass('inputRequiredWarning');
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.advanced_tuning.cleanup = function (callback) {
|
TABS.advanced_tuning.cleanup = function (callback) {
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="acroEnabled">
|
<div class="acroEnabled">
|
||||||
ACRO
|
<span i18n="auxiliaryAcroEnabled"></span>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div id="tab-auxiliary-templates">
|
<div id="tab-auxiliary-templates">
|
||||||
|
@ -63,7 +63,11 @@
|
||||||
</div>
|
</div>
|
||||||
<table>
|
<table>
|
||||||
<tr class="modeSection">
|
<tr class="modeSection">
|
||||||
<td colspan="2"><div class="modeSectionArea"><p class="modeSectionName"></p></div></td>
|
<td colspan="2">
|
||||||
|
<div class="modeSectionArea">
|
||||||
|
<p class="modeSectionName"></p>
|
||||||
|
</div>
|
||||||
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
|
@ -42,7 +42,7 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
modeSections["Flight Modes"] = ["ANGLE", "HORIZON", "MANUAL"];
|
modeSections["Flight Modes"] = ["ANGLE", "HORIZON", "MANUAL"];
|
||||||
modeSections["Navigation Modes"] = ["NAV COURSE HOLD", "NAV CRUISE", "NAV POSHOLD", "NAV RTH", "NAV WP", "GCS NAV"];
|
modeSections["Navigation Modes"] = ["NAV COURSE HOLD", "NAV CRUISE", "NAV POSHOLD", "NAV RTH", "NAV WP", "GCS NAV"];
|
||||||
modeSections["Flight Mode Modifiers"] = ["NAV ALTHOLD", "HEADING HOLD", "AIR MODE", "SOARING", "SURFACE", "TURN ASSIST"];
|
modeSections["Flight Mode Modifiers"] = ["NAV ALTHOLD", "HEADING HOLD", "AIR MODE", "SOARING", "SURFACE", "TURN ASSIST"];
|
||||||
modeSections["Fixed Wing"] = ["AUTO TUNE", "SERVO AUTOTRIM", "AUTO LEVEL", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON"];
|
modeSections["Fixed Wing"] = ["AUTO TUNE", "SERVO AUTOTRIM", "AUTO LEVEL TRIM", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON"];
|
||||||
modeSections["Multi-rotor"] = ["FPV ANGLE MIX", "TURTLE", "MC BRAKING", "HEADFREE", "HEADADJ"];
|
modeSections["Multi-rotor"] = ["FPV ANGLE MIX", "TURTLE", "MC BRAKING", "HEADFREE", "HEADADJ"];
|
||||||
modeSections["OSD Modes"] = ["OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3"];
|
modeSections["OSD Modes"] = ["OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3"];
|
||||||
modeSections["FPV Camera Modes"] = ["CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3"];
|
modeSections["FPV Camera Modes"] = ["CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3"];
|
||||||
|
|
|
@ -23,27 +23,27 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div data-step="1" class="tile step1 finished">
|
<div data-step="1" class="tile step1 finished">
|
||||||
<div class="steptitle">Step 1</div>
|
<div class="steptitle" data-i18n="stepTitle1"></div>
|
||||||
<div class="indicator"></div>
|
<div class="indicator"></div>
|
||||||
</div>
|
</div>
|
||||||
<div data-step="2" class="tile step2 active">
|
<div data-step="2" class="tile step2 active">
|
||||||
<div class="steptitle">Step 2</div>
|
<div class="steptitle" data-i18n="stepTitle2"></div>
|
||||||
<div class="indicator"></div>
|
<div class="indicator"></div>
|
||||||
</div>
|
</div>
|
||||||
<div data-step="3" class="tile step3">
|
<div data-step="3" class="tile step3">
|
||||||
<div class="steptitle">Step 3</div>
|
<div class="steptitle" data-i18n="stepTitle3"></div>
|
||||||
<div class="indicator"></div>
|
<div class="indicator"></div>
|
||||||
</div>
|
</div>
|
||||||
<div data-step="4" class="tile step4">
|
<div data-step="4" class="tile step4">
|
||||||
<div class="steptitle">Step 4</div>
|
<div class="steptitle" data-i18n="stepTitle4"></div>
|
||||||
<div class="indicator"></div>
|
<div class="indicator"></div>
|
||||||
</div>
|
</div>
|
||||||
<div data-step="5" class="tile step5">
|
<div data-step="5" class="tile step5">
|
||||||
<div class="steptitle">Step 5</div>
|
<div class="steptitle" data-i18n="stepTitle5"></div>
|
||||||
<div class="indicator"></div>
|
<div class="indicator"></div>
|
||||||
</div>
|
</div>
|
||||||
<div data-step="6" class="tile step6">
|
<div data-step="6" class="tile step6">
|
||||||
<div class="steptitle">Step 6</div>
|
<div class="steptitle" data-i18n="stepTitle6"></div>
|
||||||
<div class="indicator"></div>
|
<div class="indicator"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box grey" id="accPosAll">
|
<div class="gui_box grey" id="accPosAll">
|
||||||
|
@ -98,27 +98,27 @@
|
||||||
</div>
|
</div>
|
||||||
<table id="mag-calibrated-data" class="cf_table">
|
<table id="mag-calibrated-data" class="cf_table">
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagX"><span>Zero X</span></label></td>
|
<td><label for="MagX" data-i18n="MagXText"><span></span></label></td>
|
||||||
<td><input readonly disabled type="number" name="MagX" min="-32768" max="32767"></td>
|
<td><input readonly disabled type="number" name="MagX" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagY"><span>Zero Y</span></label></td>
|
<td><label for="MagY" data-i18n="MagYText"><span></span></label></td>
|
||||||
<td><input readonly disabled type="number" name="MagY" min="-32768" max="32767"></td>
|
<td><input readonly disabled type="number" name="MagY" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagZ"><span>Zero Z</span></label></td>
|
<td><label for="MagZ" data-i18n="MagZText"><span></span></label></td>
|
||||||
<td><input readonly disabled type="number" name="MagZ" min="-32768" max="32767"></td>
|
<td><input readonly disabled type="number" name="MagZ" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagGainX"><span>Gain X</span></label></td>
|
<td><label for="MagGainX" data-i18n="MagGainXText"><span></span></label></td>
|
||||||
<td><input readonly disabled type="number" name="MagGainX" min="-32768" max="32767"></td>
|
<td><input readonly disabled type="number" name="MagGainX" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagGainY"><span>Gain Y</span></label></td>
|
<td><label for="MagGainY" data-i18n="MagGainYText"><span></span></label></td>
|
||||||
<td><input readonly disabled type="number" name="MagGainY" min="-32768" max="32767"></td>
|
<td><input readonly disabled type="number" name="MagGainY" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagGainZ"><span>Gain Z</span></label></td>
|
<td><label for="MagGainZ" data-i18n="MagGainZText"><span></span></label></td>
|
||||||
<td><input readonly disabled type="number" name="MagGainZ" min="-32768" max="32767"></td>
|
<td><input readonly disabled type="number" name="MagGainZ" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
|
@ -137,7 +137,7 @@
|
||||||
</div>
|
</div>
|
||||||
<table id="opflow-calibrated-data" class="cf_table">
|
<table id="opflow-calibrated-data" class="cf_table">
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="OpflowScale"><span>Scale</span></label></td>
|
<td><label for="OpflowScale"><span data-i18n="OpflowScaleText"></span></label></td>
|
||||||
<td><input type="number" name="OpflowScale" min="0" max="10000"></td>
|
<td><input type="number" name="OpflowScale" min="0" max="10000"></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
|
@ -189,4 +189,4 @@
|
||||||
<h1 class="modal__title modal__title--center" data-i18n="accCalibrationProcessing"></h1>
|
<h1 class="modal__title modal__title--center" data-i18n="accCalibrationProcessing"></h1>
|
||||||
<div id="modal-opflow-countdown" class="modal__text"></div>
|
<div id="modal-opflow-countdown" class="modal__text"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
|
@ -11,7 +11,12 @@
|
||||||
<div class="wrapper"></div>
|
<div class="wrapper"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<textarea name="commands" i18n_placeholder="cliInputPlaceholder" rows="1" cols="0"></textarea>
|
<div style="display:flex;align-items:center;">
|
||||||
|
<textarea name="commands" i18n_placeholder="cliInputPlaceholder" rows="1" cols="0"></textarea>
|
||||||
|
<a class="helpiconLink" style="margin-left:5px;margin-right:5px;" href="https://github.com/iNavFlight/inav/blob/master/docs/Cli.md" target="_blank">
|
||||||
|
<div class="helpicon cf_tip" style="float:none;" data-i18n_title="cliCommandsHelp"></div>
|
||||||
|
</a>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_toolbar">
|
<div class="content_toolbar">
|
||||||
<div class="btn save_btn" style="float: left; padding-left: 15px">
|
<div class="btn save_btn" style="float: left; padding-left: 15px">
|
||||||
|
@ -23,8 +28,9 @@
|
||||||
<a class="cliDocsBtn" href="#" i18n="cliDocsBtn" target="_blank"></a>
|
<a class="cliDocsBtn" href="#" i18n="cliDocsBtn" target="_blank"></a>
|
||||||
<a class="save" href="#" i18n="cliSaveToFileBtn"></a>
|
<a class="save" href="#" i18n="cliSaveToFileBtn"></a>
|
||||||
<a class="load" href="#" i18n="cliLoadFromFileBtn"></a>
|
<a class="load" href="#" i18n="cliLoadFromFileBtn"></a>
|
||||||
<a class="clear" href="#" i18n="cliClearOutputHistoryBtn"></a>
|
<a class="copy" href="#" i18n="cliCopyToClipboardBtn"></a>
|
||||||
<a class="copy" href="#" i18n="cliCopyToClipboardBtn"></a>
|
<a class="clear" href="#" i18n="cliClearOutputHistoryBtn"></a>
|
||||||
|
<a class="diffall" href="#" i18n="cliDiffAllBtn"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
|
14
tabs/cli.js
|
@ -172,10 +172,10 @@ TABS.cli.initialize = function (callback) {
|
||||||
|
|
||||||
fs.writeFile(result, self.outputHistory, (err) => {
|
fs.writeFile(result, self.outputHistory, (err) => {
|
||||||
if (err) {
|
if (err) {
|
||||||
GUI.log('<span style="color: red">Error writing file</span>');
|
GUI.log(chrome.i18n.getMessage('ErrorWritingFile'));
|
||||||
return console.error(err);
|
return console.error(err);
|
||||||
}
|
}
|
||||||
GUI.log('File saved');
|
GUI.log(chrome.i18n.getMessage('FileSaved'));
|
||||||
});
|
});
|
||||||
|
|
||||||
});
|
});
|
||||||
|
@ -193,6 +193,12 @@ TABS.cli.initialize = function (callback) {
|
||||||
self.send(getCliCommand('msc\n', TABS.cli.cliBuffer));
|
self.send(getCliCommand('msc\n', TABS.cli.cliBuffer));
|
||||||
});
|
});
|
||||||
|
|
||||||
|
$('.tab-cli .diffall').click(function() {
|
||||||
|
self.outputHistory = "";
|
||||||
|
$('.tab-cli .window .wrapper').empty();
|
||||||
|
self.send(getCliCommand('diff all\n', TABS.cli.cliBuffer));
|
||||||
|
});
|
||||||
|
|
||||||
$('.tab-cli .clear').click(function() {
|
$('.tab-cli .clear').click(function() {
|
||||||
self.outputHistory = "";
|
self.outputHistory = "";
|
||||||
$('.tab-cli .window .wrapper').empty();
|
$('.tab-cli .window .wrapper').empty();
|
||||||
|
@ -244,7 +250,7 @@ TABS.cli.initialize = function (callback) {
|
||||||
|
|
||||||
fs.readFile(result, (err, data) => {
|
fs.readFile(result, (err, data) => {
|
||||||
if (err) {
|
if (err) {
|
||||||
GUI.log('<span style="color: red">Error reading file</span>');
|
GUI.log(chrome.i18n.getMessage('ErrorReadingFile'));
|
||||||
return console.error(err);
|
return console.error(err);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -278,7 +284,7 @@ TABS.cli.initialize = function (callback) {
|
||||||
var out_string = textarea.val();
|
var out_string = textarea.val();
|
||||||
self.history.add(out_string.trim());
|
self.history.add(out_string.trim());
|
||||||
|
|
||||||
if (out_string.trim().toLowerCase() == "cls") {
|
if (out_string.trim().toLowerCase() == "cls" || out_string.trim().toLowerCase() == "clear") {
|
||||||
self.outputHistory = "";
|
self.outputHistory = "";
|
||||||
$('.tab-cli .window .wrapper').empty();
|
$('.tab-cli .window .wrapper').empty();
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -54,28 +54,6 @@
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="board gui_box grey">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="configurationBoardAlignment"></div>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configHelp2"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="info-box" data-i18n="rollPitchAdjustmentsMoved"></div>
|
|
||||||
<div class="number">
|
|
||||||
<input id="board_align_yaw" type="number" name="board_align_yaw" step="0.1" min="-180" max="360" />
|
|
||||||
<div class="alignicon yaw"></div>
|
|
||||||
<label for="board_align_yaw" data-i18n="configurationBoardAlignmentYaw"></label>
|
|
||||||
</div>
|
|
||||||
<div class="select" style="position: relative; top: -3px;">
|
|
||||||
<select id="magalign" class="magalign">
|
|
||||||
<option value="0">Default</option>
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<div class="alignicon yaw"></div>
|
|
||||||
<label for="magalign" data-i18n="configurationSensorAlignmentMag"></label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="config-section gui_box grey other">
|
<div class="config-section gui_box grey other">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
|
|
|
@ -30,12 +30,10 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
var saveChainer = new MSPChainerClass();
|
var saveChainer = new MSPChainerClass();
|
||||||
|
|
||||||
var saveChain = [
|
var saveChain = [
|
||||||
mspHelper.saveSensorAlignment,
|
|
||||||
mspHelper.saveAccTrim,
|
mspHelper.saveAccTrim,
|
||||||
mspHelper.saveArmingConfig,
|
mspHelper.saveArmingConfig,
|
||||||
mspHelper.saveAdvancedConfig,
|
mspHelper.saveAdvancedConfig,
|
||||||
mspHelper.saveVTXConfig,
|
mspHelper.saveVTXConfig,
|
||||||
mspHelper.saveBoardAlignment,
|
|
||||||
mspHelper.saveCurrentMeterConfig,
|
mspHelper.saveCurrentMeterConfig,
|
||||||
mspHelper.saveMiscV2,
|
mspHelper.saveMiscV2,
|
||||||
saveSettings,
|
saveSettings,
|
||||||
|
@ -115,14 +113,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
let alignments = FC.getSensorAlignments();
|
|
||||||
let orientation_mag_e = $('select.magalign');
|
|
||||||
|
|
||||||
for (i = 0; i < alignments.length; i++) {
|
|
||||||
orientation_mag_e.append('<option value="' + (i + 1) + '">' + alignments[i] + '</option>');
|
|
||||||
}
|
|
||||||
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
|
||||||
|
|
||||||
// VTX
|
// VTX
|
||||||
var config_vtx = $('.config-vtx');
|
var config_vtx = $('.config-vtx');
|
||||||
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
|
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
|
||||||
|
@ -209,7 +199,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('input[name="board_align_yaw"]').val((BOARD_ALIGNMENT.yaw / 10.0).toFixed(1));
|
$('input[name="board_align_yaw"]').val((BOARD_ALIGNMENT.yaw / 10.0).toFixed(1));
|
||||||
|
|
||||||
// fill magnetometer
|
// fill magnetometer
|
||||||
$('#mag_declination').val(MISC.mag_declination);
|
//UPDATE: moved to GPS tab and hidden
|
||||||
|
//$('#mag_declination').val(MISC.mag_declination);
|
||||||
|
|
||||||
// fill battery voltage
|
// fill battery voltage
|
||||||
$('#voltagesource').val(MISC.voltage_source);
|
$('#voltagesource').val(MISC.voltage_source);
|
||||||
|
@ -264,7 +255,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$i2cSpeed.change();
|
$i2cSpeed.change();
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
MISC.mag_declination = parseFloat($('#mag_declination').val());
|
//UPDATE: moved to GPS tab and hidden
|
||||||
|
//MISC.mag_declination = parseFloat($('#mag_declination').val());
|
||||||
|
|
||||||
ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
|
ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
|
||||||
|
|
||||||
|
@ -281,8 +273,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
MISC.battery_capacity_critical = parseInt($('#battery_capacity_critical').val() * MISC.battery_capacity / 100);
|
MISC.battery_capacity_critical = parseInt($('#battery_capacity_critical').val() * MISC.battery_capacity / 100);
|
||||||
MISC.battery_capacity_unit = $('#battery_capacity_unit').val();
|
MISC.battery_capacity_unit = $('#battery_capacity_unit').val();
|
||||||
|
|
||||||
SENSOR_ALIGNMENT.align_mag = parseInt(orientation_mag_e.val());
|
|
||||||
|
|
||||||
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());
|
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());
|
||||||
|
|
||||||
googleAnalytics.sendEvent('Board', 'Accelerometer', $('#sensor-acc').children("option:selected").text());
|
googleAnalytics.sendEvent('Board', 'Accelerometer', $('#sensor-acc').children("option:selected").text());
|
||||||
|
@ -300,7 +290,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
helper.features.reset();
|
helper.features.reset();
|
||||||
helper.features.fromUI($('.tab-configuration'));
|
helper.features.fromUI($('.tab-configuration'));
|
||||||
helper.features.execute(function () {
|
helper.features.execute(function () {
|
||||||
BOARD_ALIGNMENT.yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
|
|
||||||
CURRENT_METER_CONFIG.scale = parseInt($('#currentscale').val());
|
CURRENT_METER_CONFIG.scale = parseInt($('#currentscale').val());
|
||||||
CURRENT_METER_CONFIG.offset = Math.round(parseFloat($('#currentoffset').val()) * 10);
|
CURRENT_METER_CONFIG.offset = Math.round(parseFloat($('#currentoffset').val()) * 10);
|
||||||
saveChainer.execute();
|
saveChainer.execute();
|
||||||
|
|
175
tabs/ez_tune.html
Normal file
|
@ -0,0 +1,175 @@
|
||||||
|
<!--suppress ALL -->
|
||||||
|
<div id="content-watermark"></div>
|
||||||
|
<div class="tab-ez_tune toolbar_fixed_bottom">
|
||||||
|
<div class="content_wrapper">
|
||||||
|
<div class="tab_title" data-i18n="tabEzTune"></div>
|
||||||
|
<div class="note spacebottom">
|
||||||
|
<div class="note_spacer">
|
||||||
|
<p i18n="ezTuneDisclaimer"></p>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
<div style="display: flex;">
|
||||||
|
|
||||||
|
<div>
|
||||||
|
|
||||||
|
<div class="pid-sliders-axis" style="background-color: #2a9d8f;">
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneEnabledTips"></div>
|
||||||
|
<div class="pid-switch-row">
|
||||||
|
<span data-i18n="configurationFeatureEnabled" class="bold label"></span>
|
||||||
|
<div class="checkbox no-border">
|
||||||
|
<input id="ez_tune_enabled" type="checkbox" class="ez-element toggle" />
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="pid-sliders-axis" data-axis="roll">
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneFilterHzTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneFilterHz" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_filter_hz" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="pid-sliders-axis" data-axis="pitch">
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneAxisRatioTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
|
||||||
|
<span data-i18n="ezTuneAxisRatio" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_axis_ratio" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneResponseTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneResponse" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_response" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneDampingTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneDamping" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_damping" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneStabilityTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneStability" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_stability" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneAggressivenessTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneAggressiveness" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_aggressiveness" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="pid-sliders-axis" data-axis="yaw">
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneRateTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneRate" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_rate" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div style="padding: 1em;" data-i18n="ezTuneExpoTips"></div>
|
||||||
|
<div class="pid-slider-row">
|
||||||
|
<span data-i18n="ezTuneExpo" class="bold"></span>
|
||||||
|
<div class="number no-border">
|
||||||
|
<input id="ez_tune_expo" type="number" class="ez-element" />
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="ez-tune-preview">
|
||||||
|
<h2 data-i18n="ezTunePidPreview"></h2>
|
||||||
|
<table>
|
||||||
|
<tr>
|
||||||
|
<th> </th>
|
||||||
|
<th>P</th>
|
||||||
|
<th>I</th>
|
||||||
|
<th>D</th>
|
||||||
|
<th>FF</th>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="axisRoll"></th>
|
||||||
|
<td id="preview-roll-p"></td>
|
||||||
|
<td id="preview-roll-i"></td>
|
||||||
|
<td id="preview-roll-d"></td>
|
||||||
|
<td id="preview-roll-ff"></td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="axisPitch"></th>
|
||||||
|
<td id="preview-pitch-p"></td>
|
||||||
|
<td id="preview-pitch-i"></td>
|
||||||
|
<td id="preview-pitch-d"></td>
|
||||||
|
<td id="preview-pitch-ff"></td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="axisYaw"></th>
|
||||||
|
<td id="preview-yaw-p"></td>
|
||||||
|
<td id="preview-yaw-i"></td>
|
||||||
|
<td id="preview-yaw-d"></td>
|
||||||
|
<td id="preview-yaw-ff"></td>
|
||||||
|
</tr>
|
||||||
|
</table>
|
||||||
|
<h2 data-i18n="ezTuneRatePreview"></h2>
|
||||||
|
<table>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="ezTuneRatePreviewAxis"></th>
|
||||||
|
<th data-i18n="ezTuneRatePreviewRate"></th>
|
||||||
|
<th data-i18n="ezTuneRatePreviewExpo"></th>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="axisRoll"></th>
|
||||||
|
<td id="preview-roll-rate"></td>
|
||||||
|
<td id="preview-roll-expo"></td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="axisPitch"></th>
|
||||||
|
<td id="preview-pitch-rate"></td>
|
||||||
|
<td id="preview-pitch-expo"></td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="axisYaw"></th>
|
||||||
|
<td id="preview-yaw-rate"></td>
|
||||||
|
<td id="preview-yaw-expo"></td>
|
||||||
|
</tr>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
<div class="content_toolbar">
|
||||||
|
<div class="btn save_btn">
|
||||||
|
<a class="update" href="#" data-i18n="pidTuning_ButtonSave"></a>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
161
tabs/ez_tune.js
Normal file
|
@ -0,0 +1,161 @@
|
||||||
|
/*global chrome,helper,mspHelper*/
|
||||||
|
'use strict';
|
||||||
|
|
||||||
|
TABS.ez_tune = {
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
TABS.ez_tune.initialize = function (callback) {
|
||||||
|
|
||||||
|
let loadChainer = new MSPChainerClass();
|
||||||
|
|
||||||
|
let loadChain = [
|
||||||
|
mspHelper.loadEzTune,
|
||||||
|
];
|
||||||
|
|
||||||
|
let EZ_TUNE_PID_RP_DEFAULT = [40, 75, 23, 100];
|
||||||
|
let EZ_TUNE_PID_YAW_DEFAULT = [45, 80, 0, 100];
|
||||||
|
|
||||||
|
loadChain.push(mspHelper.loadRateProfileData);
|
||||||
|
|
||||||
|
loadChainer.setChain(loadChain);
|
||||||
|
loadChainer.setExitPoint(load_html);
|
||||||
|
loadChainer.execute();
|
||||||
|
|
||||||
|
var saveChainer = new MSPChainerClass();
|
||||||
|
|
||||||
|
var saveChain = [
|
||||||
|
mspHelper.saveEzTune,
|
||||||
|
mspHelper.saveToEeprom
|
||||||
|
];
|
||||||
|
|
||||||
|
saveChainer.setChain(saveChain);
|
||||||
|
saveChainer.setExitPoint(reboot);
|
||||||
|
|
||||||
|
function reboot() {
|
||||||
|
//noinspection JSUnresolvedVariable
|
||||||
|
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||||
|
GUI.tab_switch_cleanup(function () {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function reinitialize() {
|
||||||
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
|
GUI.handleReconnect($('.tab_ez_tune a'));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (GUI.active_tab != 'ez_tune') {
|
||||||
|
GUI.active_tab = 'ez_tune';
|
||||||
|
googleAnalytics.sendAppView('Ez Tune');
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_html() {
|
||||||
|
GUI.load("./tabs/ez_tune.html", Settings.processHtml(process_html));
|
||||||
|
}
|
||||||
|
|
||||||
|
function getYawPidScale(input) {
|
||||||
|
const normalized = (input - 100) * 0.01;
|
||||||
|
|
||||||
|
return 1.0 + (normalized * 0.5);
|
||||||
|
}
|
||||||
|
|
||||||
|
function scaleRange(x, srcMin, srcMax, destMin, destMax) {
|
||||||
|
let a = (destMax - destMin) * (x - srcMin);
|
||||||
|
let b = srcMax - srcMin;
|
||||||
|
return ((a / b) + destMin);
|
||||||
|
}
|
||||||
|
|
||||||
|
function updatePreview() {
|
||||||
|
|
||||||
|
let axisRatio = $('#ez_tune_axis_ratio').val() / 100;
|
||||||
|
let response = $('#ez_tune_response').val();
|
||||||
|
let damping = $('#ez_tune_damping').val();
|
||||||
|
let stability = $('#ez_tune_stability').val();
|
||||||
|
let aggressiveness = $('#ez_tune_aggressiveness').val();
|
||||||
|
let rate = $('#ez_tune_rate').val();
|
||||||
|
let expo = $('#ez_tune_expo').val();
|
||||||
|
|
||||||
|
$('#preview-roll-p').html(Math.floor(EZ_TUNE_PID_RP_DEFAULT[0] * response / 100));
|
||||||
|
$('#preview-roll-i').html(Math.floor(EZ_TUNE_PID_RP_DEFAULT[1] * stability / 100));
|
||||||
|
$('#preview-roll-d').html(Math.floor(EZ_TUNE_PID_RP_DEFAULT[2] * damping / 100));
|
||||||
|
$('#preview-roll-ff').html(Math.floor(EZ_TUNE_PID_RP_DEFAULT[3] * aggressiveness / 100));
|
||||||
|
|
||||||
|
$('#preview-pitch-p').html(Math.floor(axisRatio * EZ_TUNE_PID_RP_DEFAULT[0] * response / 100));
|
||||||
|
$('#preview-pitch-i').html(Math.floor(axisRatio * EZ_TUNE_PID_RP_DEFAULT[1] * stability / 100));
|
||||||
|
$('#preview-pitch-d').html(Math.floor(axisRatio * EZ_TUNE_PID_RP_DEFAULT[2] * damping / 100));
|
||||||
|
$('#preview-pitch-ff').html(Math.floor(axisRatio * EZ_TUNE_PID_RP_DEFAULT[3] * aggressiveness / 100));
|
||||||
|
|
||||||
|
$('#preview-yaw-p').html(Math.floor(EZ_TUNE_PID_YAW_DEFAULT[0] * getYawPidScale(response)));
|
||||||
|
$('#preview-yaw-i').html(Math.floor(EZ_TUNE_PID_YAW_DEFAULT[1] * getYawPidScale(stability)));
|
||||||
|
$('#preview-yaw-d').html(Math.floor(EZ_TUNE_PID_YAW_DEFAULT[2] * getYawPidScale(damping)));
|
||||||
|
$('#preview-yaw-ff').html(Math.floor(EZ_TUNE_PID_YAW_DEFAULT[3] * getYawPidScale(aggressiveness)));
|
||||||
|
|
||||||
|
$('#preview-roll-rate').html(Math.floor(scaleRange(rate, 0, 200, 30, 90)) * 10 + " dps");
|
||||||
|
$('#preview-pitch-rate').html(Math.floor(scaleRange(rate, 0, 200, 30, 90)) * 10 + " dps");
|
||||||
|
$('#preview-yaw-rate').html((Math.floor(scaleRange(rate, 0, 200, 30, 90)) - 10) * 10 + " dps");
|
||||||
|
|
||||||
|
$('#preview-roll-expo').html(Math.floor(scaleRange(expo, 0, 200, 40, 100)) + "%");
|
||||||
|
$('#preview-pitch-expo').html(Math.floor(scaleRange(expo, 0, 200, 40, 100)) + "%");
|
||||||
|
$('#preview-yaw-expo').html(Math.floor(scaleRange(expo, 0, 200, 40, 100)) + "%");
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
function process_html() {
|
||||||
|
localize();
|
||||||
|
|
||||||
|
helper.tabs.init($('.tab-ez_tune'));
|
||||||
|
helper.features.updateUI($('.tab-ez_tune'), FEATURES);
|
||||||
|
|
||||||
|
$("#ez_tune_enabled").prop('checked', EZ_TUNE.enabled);
|
||||||
|
|
||||||
|
GUI.sliderize($('#ez_tune_filter_hz'), EZ_TUNE.filterHz, 10, 300);
|
||||||
|
GUI.sliderize($('#ez_tune_axis_ratio'), EZ_TUNE.axisRatio, 25, 175);
|
||||||
|
GUI.sliderize($('#ez_tune_response'), EZ_TUNE.response, 0, 200);
|
||||||
|
GUI.sliderize($('#ez_tune_damping'), EZ_TUNE.damping, 0, 200);
|
||||||
|
GUI.sliderize($('#ez_tune_stability'), EZ_TUNE.stability, 0, 200);
|
||||||
|
GUI.sliderize($('#ez_tune_aggressiveness'), EZ_TUNE.aggressiveness, 0, 200);
|
||||||
|
|
||||||
|
GUI.sliderize($('#ez_tune_rate'), EZ_TUNE.rate, 0, 200);
|
||||||
|
GUI.sliderize($('#ez_tune_expo'), EZ_TUNE.expo, 0, 200);
|
||||||
|
|
||||||
|
|
||||||
|
$('.ez-element').on('updated', function () {
|
||||||
|
updatePreview();
|
||||||
|
});
|
||||||
|
|
||||||
|
updatePreview();
|
||||||
|
|
||||||
|
GUI.simpleBind();
|
||||||
|
|
||||||
|
GUI.content_ready(callback);
|
||||||
|
|
||||||
|
$('a.update').on('click', function () {
|
||||||
|
|
||||||
|
if ($("#ez_tune_enabled").is(":checked")) {
|
||||||
|
EZ_TUNE.enabled = 1;
|
||||||
|
} else {
|
||||||
|
EZ_TUNE.enabled = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
EZ_TUNE.filterHz = $('#ez_tune_filter_hz').val();
|
||||||
|
EZ_TUNE.axisRatio = $('#ez_tune_axis_ratio').val();
|
||||||
|
EZ_TUNE.response = $('#ez_tune_response').val();
|
||||||
|
EZ_TUNE.damping = $('#ez_tune_damping').val();
|
||||||
|
EZ_TUNE.stability = $('#ez_tune_stability').val();
|
||||||
|
EZ_TUNE.aggressiveness = $('#ez_tune_aggressiveness').val();
|
||||||
|
EZ_TUNE.rate = $('#ez_tune_rate').val();
|
||||||
|
EZ_TUNE.expo = $('#ez_tune_expo').val();
|
||||||
|
|
||||||
|
saveChainer.execute();
|
||||||
|
});
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
TABS.ez_tune.cleanup = function (callback) {
|
||||||
|
if (callback) {
|
||||||
|
callback();
|
||||||
|
}
|
||||||
|
};
|
|
@ -1,20 +1,20 @@
|
||||||
<div class="tab-failsafe toolbar_fixed_bottom">
|
<div class="tab-failsafe toolbar_fixed_bottom">
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="tab_title">Failsafe</div>
|
<div class="tab_title" data-i18n="tabFailsafe">Failsafe</div>
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" data-i18n="failsafeStageTwoSettingsTitle"></div>
|
<div class="spacer_box_title" data-i18n="failsafeStageTwoSettingsTitle"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="failsafeDelay" type="number" name="failsafe_delay" data-unit="dsec" data-setting="failsafe_delay" min="0" max="200" />
|
<input id="failsafeDelay" type="number" name="failsafe_delay" data-unit="dsec" data-setting="failsafe_delay" min="0" max="200" />
|
||||||
<label><span data-i18n="failsafeDelayItem"></span></label>
|
<label><span data-i18n="failsafeDelayItem"></span></label>
|
||||||
<div for="failsafeDelay" class="helpicon cf_tip" data-i18n_title="failsafeDelayHelp"></div>
|
<div for="failsafeDelay" class="helpicon cf_tip" data-i18n_title="failsafeDelayHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<!-- radio buttons -->
|
<!-- radio buttons -->
|
||||||
<div class="subline" data-i18n="failsafeSubTitle1"></div>
|
<div class="subline" data-i18n="failsafeSubTitle1"></div>
|
||||||
<div class="radioarea pro1">
|
<div class="radioarea pro1">
|
||||||
<div class="radiobuttons"><input class="procedure" id="drop" name="group1" type="radio"/>
|
<div class="radiobuttons"><input class="procedure" id="drop" name="group1" type="radio" />
|
||||||
<label for="drop" data-i18n="failsafeProcedureItemSelect2"></label>
|
<label for="drop" data-i18n="failsafeProcedureItemSelect2"></label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -35,18 +35,18 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="radioarea pro4">
|
<div class="radioarea pro4">
|
||||||
<div class="radiobuttons"><input class="procedure" id="rth" name="group1" type="radio"/>
|
<div class="radiobuttons"><input class="procedure" id="rth" name="group1" type="radio" />
|
||||||
<label for="rth" data-i18n="failsafeProcedureItemSelect3"></label>
|
<label for="rth" data-i18n="failsafeProcedureItemSelect3"></label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="radioarea pro5">
|
<div class="radioarea pro5">
|
||||||
<div class="radiobuttons"><input class="procedure" id="nothing" name="group1" type="radio"/>
|
<div class="radiobuttons"><input class="procedure" id="nothing" name="group1" type="radio" />
|
||||||
<label for="nothing" data-i18n="failsafeProcedureItemSelect4"></label>
|
<label for="nothing" data-i18n="failsafeProcedureItemSelect4"></label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<!-- Minimum Failsafe Distance controls -->
|
<!-- Minimum Failsafe Distance controls -->
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<div class="numberspacer" >
|
<div class="numberspacer">
|
||||||
<input type="checkbox" name="failsafe_use_minimum_distance" class="toggle" id="failsafe_use_minimum_distance" />
|
<input type="checkbox" name="failsafe_use_minimum_distance" class="toggle" id="failsafe_use_minimum_distance" />
|
||||||
</div>
|
</div>
|
||||||
<label for="failsafe_use_minimum_distance"><span data-i18n="failsafeUseMinimumDistanceItem"></span>
|
<label for="failsafe_use_minimum_distance"><span data-i18n="failsafeUseMinimumDistanceItem"></span>
|
||||||
|
@ -73,4 +73,4 @@
|
||||||
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
|
@ -52,9 +52,9 @@ TABS.firmware_flasher.initialize = function (callback) {
|
||||||
|
|
||||||
$('input.show_development_releases').click(function() {
|
$('input.show_development_releases').click(function() {
|
||||||
let selectedTarget = String($('select[name="board"]').val());
|
let selectedTarget = String($('select[name="board"]').val());
|
||||||
GUI.log("selected target = " + selectedTarget);
|
GUI.log(chrome.i18n.getMessage('selectedTarget') + selectedTarget);
|
||||||
buildBoardOptions();
|
buildBoardOptions();
|
||||||
GUI.log("toggled RCs");
|
GUI.log(chrome.i18n.getMessage('toggledRCs'));
|
||||||
if (selectedTarget === "0") {
|
if (selectedTarget === "0") {
|
||||||
TABS.firmware_flasher.getTarget();
|
TABS.firmware_flasher.getTarget();
|
||||||
} else {
|
} else {
|
||||||
|
@ -274,7 +274,7 @@ TABS.firmware_flasher.initialize = function (callback) {
|
||||||
$('a.load_remote_file').click(function (evt) {
|
$('a.load_remote_file').click(function (evt) {
|
||||||
|
|
||||||
if ($('select[name="firmware_version"]').val() == "0") {
|
if ($('select[name="firmware_version"]').val() == "0") {
|
||||||
GUI.log("<b>No firmware selected to load</b>");
|
GUI.log(chrome.i18n.getMessage('noFirmwareSelectedToLoad'));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -402,7 +402,7 @@ TABS.firmware_flasher.initialize = function (callback) {
|
||||||
STM32.connect(port, baud, parsed_hex, options);
|
STM32.connect(port, baud, parsed_hex, options);
|
||||||
} else {
|
} else {
|
||||||
console.log('Please select valid serial port');
|
console.log('Please select valid serial port');
|
||||||
GUI.log('<span style="color: red">Please select valid serial port</span>');
|
GUI.log(chrome.i18n.getMessage('selectValidSerialPort'));
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
STM32DFU.connect(usbDevices, parsed_hex, options);
|
STM32DFU.connect(usbDevices, parsed_hex, options);
|
||||||
|
@ -452,7 +452,7 @@ TABS.firmware_flasher.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
console.log('You don\'t have write permissions for this file, sorry.');
|
console.log('You don\'t have write permissions for this file, sorry.');
|
||||||
GUI.log('You don\'t have <span style="color: red">write permissions</span> for this file');
|
GUI.log(chrome.i18n.getMessage('writePermissionsForFile'));
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
@ -635,14 +635,14 @@ TABS.firmware_flasher.cleanup = function (callback) {
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.firmware_flasher.getTarget = function() {
|
TABS.firmware_flasher.getTarget = function() {
|
||||||
GUI.log("Attempting automatic target selection");
|
GUI.log(chrome.i18n.getMessage('automaticTargetSelect'));
|
||||||
|
|
||||||
var selected_baud = parseInt($('#baud').val());
|
var selected_baud = parseInt($('#baud').val());
|
||||||
var selected_port = $('#port').find('option:selected').data().isManual ? $('#port-override').val() : String($('#port').val());
|
var selected_port = $('#port').find('option:selected').data().isManual ? $('#port-override').val() : String($('#port').val());
|
||||||
|
|
||||||
if (selected_port !== 'DFU') {
|
if (selected_port !== 'DFU') {
|
||||||
if (selected_port == '0') {
|
if (selected_port == '0') {
|
||||||
GUI.log("Cannot prefetch target: No port");
|
GUI.log(chrome.i18n.getMessage('targetPrefetchFailNoPort'));
|
||||||
} else {
|
} else {
|
||||||
console.log('Connecting to: ' + selected_port);
|
console.log('Connecting to: ' + selected_port);
|
||||||
GUI.connecting_to = selected_port;
|
GUI.connecting_to = selected_port;
|
||||||
|
@ -654,7 +654,7 @@ TABS.firmware_flasher.getTarget = function() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
GUI.log("Cannot prefetch target: Flight Controller in DFU");
|
GUI.log(chrome.i18n.getMessage('targetPrefetchFailDFU'));
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -686,7 +686,7 @@ TABS.firmware_flasher.onOpen = function(openInfo) {
|
||||||
// disconnect after 10 seconds with error if we don't get IDENT data
|
// disconnect after 10 seconds with error if we don't get IDENT data
|
||||||
helper.timeout.add('connecting', function () {
|
helper.timeout.add('connecting', function () {
|
||||||
if (!CONFIGURATOR.connectionValid) {
|
if (!CONFIGURATOR.connectionValid) {
|
||||||
GUI.log("Cannot prefetch target: " + chrome.i18n.getMessage('noConfigurationReceived'));
|
GUI.log(chrome.i18n.getMessage('targetPrefetchFail') + chrome.i18n.getMessage('noConfigurationReceived'));
|
||||||
|
|
||||||
TABS.firmware_flasher.closeTempConnection();
|
TABS.firmware_flasher.closeTempConnection();
|
||||||
}
|
}
|
||||||
|
@ -709,7 +709,7 @@ TABS.firmware_flasher.onOpen = function(openInfo) {
|
||||||
if (CONFIG.flightControllerIdentifier == 'INAV') {
|
if (CONFIG.flightControllerIdentifier == 'INAV') {
|
||||||
MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () {
|
||||||
if (semver.lt(CONFIG.flightControllerVersion, "5.0.0")) {
|
if (semver.lt(CONFIG.flightControllerVersion, "5.0.0")) {
|
||||||
GUI.log("Cannot prefetch target: INAV Firmware too old");
|
GUI.log(chrome.i18n.getMessage('targetPrefetchFailOld'));
|
||||||
TABS.firmware_flasher.closeTempConnection();
|
TABS.firmware_flasher.closeTempConnection();
|
||||||
} else {
|
} else {
|
||||||
mspHelper.getCraftName(function(name) {
|
mspHelper.getCraftName(function(name) {
|
||||||
|
@ -721,13 +721,13 @@ TABS.firmware_flasher.onOpen = function(openInfo) {
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
GUI.log("Cannot prefetch target: Non-INAV Firmware");
|
GUI.log(chrome.i18n.getMessage('targetPrefetchFailNonINAV'));
|
||||||
TABS.firmware_flasher.closeTempConnection();
|
TABS.firmware_flasher.closeTempConnection();
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
GUI.log("Cannot prefetch target: " + chrome.i18n.getMessage('serialPortOpenFail'));
|
GUI.log(chrome.i18n.getMessage('targetPrefetchFail') + chrome.i18n.getMessage('serialPortOpenFail'));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -736,7 +736,7 @@ TABS.firmware_flasher.onValidFirmware = function() {
|
||||||
MSP.send_message(MSPCodes.MSP_BUILD_INFO, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_BUILD_INFO, false, false, function () {
|
||||||
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, function () {
|
||||||
$('select[name="board"] option[value=' + CONFIG.target + ']').attr("selected", "selected");
|
$('select[name="board"] option[value=' + CONFIG.target + ']').attr("selected", "selected");
|
||||||
GUI.log("Target prefetch successful: " + CONFIG.target);
|
GUI.log(chrome.i18n.getMessage('targetPrefetchsuccessful') + CONFIG.target);
|
||||||
|
|
||||||
TABS.firmware_flasher.closeTempConnection();
|
TABS.firmware_flasher.closeTempConnection();
|
||||||
$('select[name="board"]').change();
|
$('select[name="board"]').change();
|
||||||
|
|
|
@ -20,7 +20,6 @@
|
||||||
<label for="feature-7"><span data-i18n="featureGPS"></span></label>
|
<label for="feature-7"><span data-i18n="featureGPS"></span></label>
|
||||||
<div for="feature-7" class="helpicon cf_tip" data-i18n_title="featureGPSTip"></div>
|
<div for="feature-7" class="helpicon cf_tip" data-i18n_title="featureGPSTip"></div>
|
||||||
</div>
|
</div>
|
||||||
<div id="nmeaWarning" data-i18n="nmeaWarning" class="warning-box"></div>
|
|
||||||
<div class="select">
|
<div class="select">
|
||||||
<select id="gps_protocol" class="gps_protocol">
|
<select id="gps_protocol" class="gps_protocol">
|
||||||
<!-- list generated here -->
|
<!-- list generated here -->
|
||||||
|
@ -41,6 +40,14 @@
|
||||||
<input type="checkbox" class="toggle update_preview" data-setting="gps_ublox_use_galileo" data-live="true">
|
<input type="checkbox" class="toggle update_preview" data-setting="gps_ublox_use_galileo" data-live="true">
|
||||||
<label for="gps_use_galileo"><span data-i18n="configurationGPSUseGalileo"></span></label>
|
<label for="gps_use_galileo"><span data-i18n="configurationGPSUseGalileo"></span></label>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" data-setting="gps_ublox_use_beidou" data-live="true">
|
||||||
|
<label for="gps_use_beidou"><span data-i18n="configurationGPSUseBeidou"></span></label>
|
||||||
|
</div>
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" data-setting="gps_ublox_use_glonass" data-live="true">
|
||||||
|
<label for="gps_use_glonass"><span data-i18n="configurationGPSUseGlonass"></span></label>
|
||||||
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="tzOffset" data-setting="tz_offset" data-unit="tzmins" data-setting-multiplier="1" step="1" min="-1440" max="1440" />
|
<input type="number" id="tzOffset" data-setting="tz_offset" data-unit="tzmins" data-setting-multiplier="1" step="1" min="-1440" max="1440" />
|
||||||
<label for="tzOffset"><span data-i18n="tzOffset"></span></label>
|
<label for="tzOffset"><span data-i18n="tzOffset"></span></label>
|
||||||
|
|
|
@ -76,11 +76,6 @@ TABS.gps.initialize = function (callback) {
|
||||||
|
|
||||||
gps_protocol_e.change(function () {
|
gps_protocol_e.change(function () {
|
||||||
MISC.gps_type = parseInt($(this).val());
|
MISC.gps_type = parseInt($(this).val());
|
||||||
if (MISC.gps_type == 0) {
|
|
||||||
$('#nmeaWarning').show();
|
|
||||||
} else {
|
|
||||||
$('#nmeaWarning').hide();
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
gps_protocol_e.val(MISC.gps_type);
|
gps_protocol_e.val(MISC.gps_type);
|
||||||
|
|
|
@ -8,14 +8,16 @@
|
||||||
</div>
|
</div>
|
||||||
<div class="community">
|
<div class="community">
|
||||||
<ul class="communityDiscordSupport"><a href="https://discord.gg/peg2hhbYwN" target="_blank"><i class="fab fa-discord" aria-hidden="true"></i><span i18n="communityDiscordServer"></span></a></ul>
|
<ul class="communityDiscordSupport"><a href="https://discord.gg/peg2hhbYwN" target="_blank"><i class="fab fa-discord" aria-hidden="true"></i><span i18n="communityDiscordServer"></span></a></ul>
|
||||||
<ul class="communityTelegramSupport"><a href="https://t.me/INAVFlight" target="_blank"><i class="fab fa-telegram" aria-hidden="true"></i><span i18n="communityTelegramSupport"></span></a></ul>
|
<!-- <ul class="communityTelegramSupport"><a href="https://t.me/INAVFlight" target="_blank"><i class="fab fa-telegram" aria-hidden="true"></i><span i18n="communityTelegramSupport"></span></a></ul> -->
|
||||||
<ul class="communityFacebookSupport"><a href="https://www.facebook.com/groups/INAVOfficial" target="_blank"><i class="fab fa-facebook" aria-hidden="true"></i><span i18n="communityFacebookSupport"></span></a></ul>
|
<ul class="communityFacebookSupport"><a href="https://www.facebook.com/groups/INAVOfficial" target="_blank"><i class="fab fa-facebook" aria-hidden="true"></i><span i18n="communityFacebookSupport"></span></a></ul>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_mid">
|
<div class="content_mid">
|
||||||
<div class="column half text1">
|
<div class="column half text1">
|
||||||
<div class="wrap">
|
<div class="wrap">
|
||||||
<h2>Hardware</h2>
|
<h2 i18n="defaultWelcomeHead"></h2>
|
||||||
<div i18n="defaultWelcomeText"></div>
|
<div i18n="defaultWelcomeText"></div>
|
||||||
|
<h2 i18n="defaultWelcomeHead2" style="margin-top: 1em;"></h2>
|
||||||
|
<div i18n="defaultWelcomeText2"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="column half text2">
|
<div class="column half text2">
|
||||||
|
@ -25,13 +27,6 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_foot">
|
<div class="content_foot"></div>
|
||||||
<div class="sponsors">
|
|
||||||
<div class="title" i18n="defaultSponsorsHead"></div>
|
|
||||||
<ul>
|
|
||||||
<li><a href="http://www.mateksys.com" title="www.mateksys.com" target="_blank"><img src="./images/partner/mateksys.png" alt="MATEK Systems" height="35" /></a></li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
|
@ -26,19 +26,19 @@
|
||||||
<div class="block"></div>
|
<div class="block"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="colorDefineSliders">
|
<div class="colorDefineSliders">
|
||||||
<div class="">Color setup</div>
|
<div class="" i18n="ledStripColorSetupTitle"></div>
|
||||||
<div class="colorDefineSliderContainer">
|
<div class="colorDefineSliderContainer">
|
||||||
<Label class="colorDefineSliderLabel">H</Label>
|
<Label class="colorDefineSliderLabel" i18n="ledStripH"></Label>
|
||||||
<input class="sliderHSV" type="range" min="0" max="359" value="0">
|
<input class="sliderHSV" type="range" min="0" max="359" value="0">
|
||||||
<Label class="colorDefineSliderValue Hvalue">0</Label>
|
<Label class="colorDefineSliderValue Hvalue">0</Label>
|
||||||
</div>
|
</div>
|
||||||
<div class="colorDefineSliderContainer">
|
<div class="colorDefineSliderContainer">
|
||||||
<Label class="colorDefineSliderLabel">S</Label>
|
<Label class="colorDefineSliderLabel" i18n="ledStripS"></Label>
|
||||||
<input class="sliderHSV" type="range" min="0" max="255" value="0">
|
<input class="sliderHSV" type="range" min="0" max="255" value="0">
|
||||||
<Label class="colorDefineSliderValue Svalue">0</Label>
|
<Label class="colorDefineSliderValue Svalue">0</Label>
|
||||||
</div>
|
</div>
|
||||||
<div class="colorDefineSliderContainer">
|
<div class="colorDefineSliderContainer">
|
||||||
<Label class="colorDefineSliderLabel">V</Label>
|
<Label class="colorDefineSliderLabel" i18n="ledStripV"></Label>
|
||||||
<input class="sliderHSV" type="range" min="0" max="255" value="0">
|
<input class="sliderHSV" type="range" min="0" max="255" value="0">
|
||||||
<Label class="colorDefineSliderValue Vvalue">0</Label>
|
<Label class="colorDefineSliderValue Vvalue">0</Label>
|
||||||
</div>
|
</div>
|
||||||
|
@ -46,151 +46,151 @@
|
||||||
<div class="controls">
|
<div class="controls">
|
||||||
<div class="wires-remaining">
|
<div class="wires-remaining">
|
||||||
<div></div>
|
<div></div>
|
||||||
Remaining
|
<span i18n="ledStripRemainingText"></span>
|
||||||
</div>
|
</div>
|
||||||
<button class="funcClear">Clear selected</button>
|
<button class="funcClear" i18n="ledStripClearSelectedButton"></button>
|
||||||
<button class="funcClearAll">Clear ALL</button>
|
<button class="funcClearAll" i18n="ledStripClearAllButton"></button>
|
||||||
|
|
||||||
|
<div class="section" i18n="ledStripFunctionSection"></div>
|
||||||
|
|
||||||
|
|
||||||
<div class="section">LED Functions</div>
|
|
||||||
|
|
||||||
|
|
||||||
<div class="select">
|
<div class="select">
|
||||||
<span class="color_section">Function</span>
|
<span class="color_section" i18n="ledStripFunctionTitle"></span>
|
||||||
<select class="functionSelect">
|
<select class="functionSelect">
|
||||||
<option value="">None</option>
|
<option value="" i18n="ledStripFunctionNoneOption"></option>
|
||||||
<option value="function-c" class="">Color</option>
|
<option value="function-c" class="" i18n="ledStripFunctionColorOption"></option>
|
||||||
<option value="function-f" class="">Modes & Orientation</option>
|
<option value="function-f" class="" i18n="ledStripFunctionModesOption"></option>
|
||||||
<option value="function-a" class="">Arm State</option>
|
<option value="function-a" class="" i18n="ledStripFunctionArmOption"></option>
|
||||||
<option value="function-l" class="extra_functions20">Battery</option>
|
<option value="function-l" class="extra_functions20" i18n="ledStripFunctionBatteryOption"></option>
|
||||||
<option value="function-s" class="extra_functions20">RSSI</option>
|
<option value="function-s" class="extra_functions20" i18n="ledStripFunctionRSSIOption"></option>
|
||||||
<option value="function-g" class="extra_functions20">GPS</option>
|
<option value="function-g" class="extra_functions20" i18n="ledStripFunctionGPSOption"></option>
|
||||||
<option value="function-r" class="">Ring</option>
|
<option value="function-r" class="" i18n="ledStripFunctionRingOption"></option>
|
||||||
<option value="function-h" class="channel_info">Channel</option>
|
<option value="function-h" class="channel_info" i18n="ledStripFunctionChannelOption"></option>
|
||||||
</select>
|
</select>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
|
||||||
<div class="modifiers">
|
<div class="modifiers">
|
||||||
<span class="color_section">Color modifier</span>
|
<span class="color_section" i18n="ledStripColorModifierTitle"></span>
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<input type="checkbox" name="ThrottleHue" class="toggle function-t" />
|
<input type="checkbox" name="ThrottleHue" class="toggle function-t" />
|
||||||
<label> <span>Throttle</span></label>
|
<label> <span i18n="ledStripThrottleText"></span></label>
|
||||||
</div>
|
</div>
|
||||||
<div class="checkbox extra_functions20">
|
<div class="checkbox extra_functions20">
|
||||||
<input type="checkbox" name="LarsonScanner" class="toggle function-o" />
|
<input type="checkbox" name="LarsonScanner" class="toggle function-o" />
|
||||||
<label> <span>Larson scanner</span></label>
|
<label> <span i18n="ledStripLarsonscannerText"></span></label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="blinkers extra_functions20">
|
<div class="blinkers extra_functions20">
|
||||||
<span class="color_section">Blink</span>
|
<span class="color_section" i18n="ledStripBlinkTitle"></span>
|
||||||
<div class="checkbox blinkOverlay">
|
<div class="checkbox blinkOverlay">
|
||||||
<input type="checkbox" name="blink" class="toggle function-b" />
|
<input type="checkbox" name="blink" class="toggle function-b" />
|
||||||
<label> <span>Blink always</span></label>
|
<label> <span i18n="ledStripBlinkAlwaysOverlay"></span></label>
|
||||||
</div>
|
</div>
|
||||||
<div class="checkbox landingBlinkOverlay">
|
<div class="checkbox landingBlinkOverlay">
|
||||||
<input type="checkbox" name="landingBlink" class="toggle function-n" />
|
<input type="checkbox" name="landingBlink" class="toggle function-n" />
|
||||||
<label> <span>Blink on landing</span></label>
|
<label> <span i18n="ledStripBlinkLandingOverlay"></span></label>
|
||||||
</div>
|
</div>
|
||||||
<span class="color_section">Strobe</span>
|
<span class="color_section" i18n="ledStripStrobeText"></span>
|
||||||
<div class="checkbox strobeOverlay">
|
<div class="checkbox strobeOverlay">
|
||||||
<input type="checkbox" name="strobe" class="toggle function-e" />
|
<input type="checkbox" name="strobe" class="toggle function-e" />
|
||||||
<label> <span>Enable strobe light effect</span></label>
|
<label> <span i18n="ledStripEnableStrobeLightEffectText"></span></label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="overlays">
|
<div class="overlays">
|
||||||
<span class="color_section">Overlay</span>
|
<span class="color_section" i18n="ledStripOverlayTitle"></span>
|
||||||
<div class="checkbox warningOverlay">
|
<div class="checkbox warningOverlay">
|
||||||
<input type="checkbox" name="Warnings" class="toggle function-w" />
|
<input type="checkbox" name="Warnings" class="toggle function-w" />
|
||||||
<label> <span>Warnings</span></label>
|
<label> <span i18n="ledStripWarningsOverlay"></span></label>
|
||||||
</div>
|
</div>
|
||||||
<div class="checkbox indicatorOverlay">
|
<div class="checkbox indicatorOverlay">
|
||||||
<input type="checkbox" name="Indicator" class="toggle function-i" />
|
<input type="checkbox" name="Indicator" class="toggle function-i" />
|
||||||
<label> <span>Indicator</span></label>
|
<label> <span i18n="ledStripIndecatorOverlay"></span></label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="channel_info">
|
<div class="channel_info">
|
||||||
<span class="color_section">Select Channel from color list</span>
|
<span class="color_section" i18n="ledStripSelectChannelFromColorList"></span>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="mode_colors">
|
<div class="mode_colors">
|
||||||
<div class="section">Mode colors</div>
|
<div class="section" i18n="ledStripModeColorsTitle"></div>
|
||||||
|
|
||||||
<select class="modeSelect">
|
<select id="ledStripModeColorsModeSelect" class="modeSelect">
|
||||||
<option value="0">Orientation</option>
|
<option value="0" i18n="ledStripModeColorsModeOrientation"></option>
|
||||||
<option value="1">Headfree</option>
|
<option value="1" i18n="ledStripModeColorsModeHeadfree"></option>
|
||||||
<option value="2">Horizon</option>
|
<option value="2" i18n="ledStripModeColorsModeHorizon"></option>
|
||||||
<option value="3">Angle</option>
|
<option value="3" i18n="ledStripModeColorsModeAngle"></option>
|
||||||
<option value="4">Mag</option>
|
<option value="4" i18n="ledStripModeColorsModeMag"></option>
|
||||||
<option value="5">Baro</option>
|
<option value="5" i18n="ledStripModeColorsModeBaro"></option>
|
||||||
</select>
|
</select>
|
||||||
|
|
||||||
<button class="mode_color-0-0 dir-n">N</button>
|
<button class="mode_color-0-0 dir-n" i18n="ledStripDirN"></button>
|
||||||
<button class="mode_color-0-1 dir-e">E</button>
|
<button class="mode_color-0-1 dir-e" i18n="ledStripDirE"></button>
|
||||||
<button class="mode_color-0-2 dir-s">S</button>
|
<button class="mode_color-0-2 dir-s" i18n="ledStripDirS"></button>
|
||||||
<button class="mode_color-0-3 dir-w">W</button>
|
<button class="mode_color-0-3 dir-w" i18n="ledStripDirW"></button>
|
||||||
<button class="mode_color-0-4 dir-u">U</button>
|
<button class="mode_color-0-4 dir-u" i18n="ledStripDirU"></button>
|
||||||
<button class="mode_color-0-5 dir-d">D</button>
|
<button class="mode_color-0-5 dir-d" i18n="ledStripDirD"></button>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="section">LED Orientation and Color</div>
|
<div class="section" i18n="ledStripModesOrientationTitle"></div>
|
||||||
<div class="directions">
|
<div class="directions">
|
||||||
<button class="dir-n">N</button>
|
<button class="dir-n" i18n="ledStripDirN"></button>
|
||||||
<button class="dir-e">E</button>
|
<button class="dir-e" i18n="ledStripDirE"></button>
|
||||||
<button class="dir-s">S</button>
|
<button class="dir-s" i18n="ledStripDirS"></button>
|
||||||
<button class="dir-w">W</button>
|
<button class="dir-w" i18n="ledStripDirW"></button>
|
||||||
<button class="dir-u">U</button>
|
<button class="dir-u" i18n="ledStripDirU"></button>
|
||||||
<button class="dir-d">D</button>
|
<button class="dir-d" i18n="ledStripDirD"></button>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="colors">
|
<div class="colors">
|
||||||
<button class="color-0" title="black">0</button>
|
<button class="color-0" i18n_title="colorBlack">0</button>
|
||||||
<button class="color-1" title="white">1</button>
|
<button class="color-1" i18n_title="colorWhite">1</button>
|
||||||
<button class="color-2" title="red">2</button>
|
<button class="color-2" i18n_title="colorRed">2</button>
|
||||||
<button class="color-3" title="orange">3</button>
|
<button class="color-3" i18n_title="colorOrange">3</button>
|
||||||
<button class="color-4" title="yellow">4</button>
|
<button class="color-4" i18n_title="colorYellow">4</button>
|
||||||
<button class="color-5" title="lime green">5</button>
|
<button class="color-5" i18n_title="colorLimeGreen">5</button>
|
||||||
<button class="color-6" title="green">6</button>
|
<button class="color-6" i18n_title="colorGreen">6</button>
|
||||||
<button class="color-7" title="mint green">7</button>
|
<button class="color-7" i18n_title="colorMintGreen">7</button>
|
||||||
<button class="color-8" title="cyan">8</button>
|
<button class="color-8" i18n_title="colorCyan">8</button>
|
||||||
<button class="color-9" title="light blue">9</button>
|
<button class="color-9" i18n_title="colorLightBlue">9</button>
|
||||||
<button class="color-10" title="blue">10</button>
|
<button class="color-10" i18n_title="colorBlue">10</button>
|
||||||
<button class="color-11" title="dark violet">11</button>
|
<button class="color-11" i18n_title="colorDarkViolet">11</button>
|
||||||
<button class="color-12" title="magenta">12</button>
|
<button class="color-12" i18n_title="colorMagenta">12</button>
|
||||||
<button class="color-13" title="deep pink">13</button>
|
<button class="color-13" i18n_title="colorDeepPink">13</button>
|
||||||
<button class="color-14" title="black">14</button>
|
<button class="color-14" i18n_title="colorBlack">14</button>
|
||||||
<button class="color-15" title="black">15</button>
|
<button class="color-15" i18n_title="colorBlack">15</button>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="special_colors mode_colors">
|
<div class="special_colors mode_colors">
|
||||||
<div class="section">Special colors</div>
|
<div class="section" i18n="ledStripModesSpecialColorsTitle"></div>
|
||||||
<button class="mode_color-6-0" title="green">Disarmed</button>
|
<button class="mode_color-6-0" i18n_title="colorGreen" i18n="ledStripModeColorsModeDisarmed"></button>
|
||||||
<button class="mode_color-6-1" title="blue">Armed</button>
|
<button class="mode_color-6-1" i18n_title="colorBlue" i18n="ledStripModeColorsModeArmed"></button>
|
||||||
<button class="mode_color-6-2" title="white">Animation</button>
|
<button class="mode_color-6-2" i18n_title="colorWhite" i18n="ledStripModeColorsModeAnimation"></button>
|
||||||
<!-- button class="mode_color-6-3" title="black">Background</button -->
|
<!-- button class="mode_color-6-3" i18n_title="colorBlack">Background</button -->
|
||||||
<button class="mode_color-6-4" title="black">Blink background</button>
|
<button class="mode_color-6-4" i18n_title="colorBlack" i18n="ledStripModeColorsModeBlinkBg"></button>
|
||||||
<button class="mode_color-6-5" title="red">GPS: no sats</button>
|
<button class="mode_color-6-5" i18n_title="colorRed" i18n="ledStripModeColorsModeGPSNoSats"></button>
|
||||||
<button class="mode_color-6-6" title="orange">GPS: no lock</button>
|
<button class="mode_color-6-6" i18n_title="colorOrange" i18n="ledStripModeColorsModeGPSNoLock"></button>
|
||||||
<button class="mode_color-6-7" title="green">GPS: locked</button>
|
<button class="mode_color-6-7" i18n_title="colorGreen" i18n="ledStripModeColorsModeGPSLocked"></button>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="section">LED Strip Wiring</div>
|
<div class="section" i18n="ledStripWiring"></div>
|
||||||
<div class="wiringMode">
|
<div class="wiringMode">
|
||||||
<button class="funcWire w100">Wire Ordering Mode</button>
|
<button class="funcWire w100" i18n="ledStripWiringMode"></button>
|
||||||
</div>
|
</div>
|
||||||
<div class="wiringControls">
|
<div class="wiringControls">
|
||||||
<button class="funcWireClearSelect w50">Clear selected</button>
|
<button class="funcWireClearSelect w50" i18n="ledStripWiringClearControl"></button>
|
||||||
<button class="funcWireClear w50">Clear ALL Wiring</button>
|
<button class="funcWireClear w50" i18n="ledStripWiringClearAllControl"></button>
|
||||||
</div>
|
</div>
|
||||||
<p>LEDs without wire ordering number will not be saved.</p>
|
<p i18n="ledStripWiringMessage"></p>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="colorControls">
|
<div class="colorControls">
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_toolbar">
|
<div class="content_toolbar">
|
||||||
|
@ -198,4 +198,4 @@
|
||||||
<a class="save" href="#" i18n="ledStripButtonSave"></a>
|
<a class="save" href="#" i18n="ledStripButtonSave"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
|
@ -1,129 +1,202 @@
|
||||||
<div class="tab-magnetometer">
|
<div class="tab-magnetometer toolbar_fixed_bottom">
|
||||||
<div class="content_wrapper" style="height: calc(80% - 40px)">
|
<div class="content_wrapper">
|
||||||
<div class="tab_title" data-i18n="tabMagnetometer">Magnetometer</div>
|
<div class="tab_title" data-i18n="tabMagnetometer">Magnetometer</div>
|
||||||
<div class="note spacebottom">
|
<div class="note spacebottom">
|
||||||
<div class="note_spacer">
|
<div class="note_spacer">
|
||||||
<p i18n="magnetometerHelp"></p>
|
<p i18n="magnetometerHelp"></p>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div style="height: calc(100% - 150px);">
|
<div class="cf_column tab-magnetometer-left-wrapper">
|
||||||
<div id="model">
|
<div class="model-and-info">
|
||||||
<div class="model-and-info">
|
<div id="interactive_block">
|
||||||
<div id="interactive_block">
|
<div id="canvas_wrapper">
|
||||||
<div id="canvas_wrapper">
|
<canvas id="canvas"></canvas>
|
||||||
<canvas id="canvas"></canvas>
|
<div class="attitude_info">
|
||||||
|
<dl>
|
||||||
|
<dt>Heading:</dt>
|
||||||
|
<dd class="heading"> </dd>
|
||||||
|
<dt>Pitch:</dt>
|
||||||
|
<dd class="pitch"> </dd>
|
||||||
|
<dt>Roll:</dt>
|
||||||
|
<dd class="roll"> </dd>
|
||||||
|
</dl>
|
||||||
</div>
|
</div>
|
||||||
<a class="reset" href="#" data-i18n="initialSetupButtonResetZaxis"></a>
|
<div class="attitude_note1" >(Values according to <b>saved</b> settings)</div>
|
||||||
|
<div class="attitude_note2" >(North: 0, East: 90, South: 180, West: 270)</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="config-section gui_box grey">
|
<div class="cf_column tab-magnetometer-right-wrapper">
|
||||||
<div class="spacer_box">
|
<div class="config-section gui_box grey">
|
||||||
<div id="alignment-info" class="info-box">
|
<div class="spacer_box">
|
||||||
<span data-i18n="magnetometerInfo"></span>
|
<div id="board-alignment-info" class="info-box">
|
||||||
</div>
|
<span data-i18n="boardInfo"></span>
|
||||||
<div class="select" style="display: flex; justify-content: left;">
|
</div>
|
||||||
<select id="magalign" class="magalign">
|
|
||||||
<option value="0">Default</option>
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<label for="magalign" data-i18n="magnetometerOrientationPreset"></label>
|
|
||||||
</div>
|
|
||||||
<div class="select" style="display: flex; justify-content: left;">
|
|
||||||
<select id="element_to_show">
|
|
||||||
<option value="0" selected>Magnetometer</option>
|
|
||||||
<option value="1">XYZ</option>
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<label for="element_to_show" data-i18n="magnetometerElementToShow"></label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<table class="axis-table">
|
<table class="axis-table">
|
||||||
<thead>
|
<thead>
|
||||||
<tr>
|
<tr>
|
||||||
<td style="width: 5%; padding-bottom: 10px;">
|
<td style="width: 5%; padding-bottom: 10px;">
|
||||||
<p class="table-title">
|
<p class="table-title">
|
||||||
Axis
|
<span data-i18n="axisTableTitleAxis"></span>
|
||||||
</p>
|
</p>
|
||||||
</td>
|
</td>
|
||||||
<td style="width: 90%; padding-bottom: 10px;">
|
<td style="width: 90%; padding-bottom: 10px;">
|
||||||
<p class="table-title">
|
<p class="table-title">
|
||||||
Slider
|
<span data-i18n="axisTableTitleSlider"></span>
|
||||||
</p>
|
</p>
|
||||||
</td>
|
</td>
|
||||||
<td style="width: 5%; padding-bottom: 10px;">
|
<td style="width: 5%; padding-bottom: 10px;">
|
||||||
<a class="table-title">
|
<a class="table-title">
|
||||||
Value [degree]
|
<span data-i18n="axisTableTitleValue"></span>
|
||||||
</a>
|
</a>
|
||||||
|
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
</thead>
|
</thead>
|
||||||
<tbody>
|
<tbody>
|
||||||
<tr>
|
<tr>
|
||||||
<td class="info">
|
<td class="info">
|
||||||
<p class="title" data-i18n="configurationSensorAlignmentMagPitch"></p>
|
<p class="title" data-i18n="configurationSensorAlignmentMagRoll"></p>
|
||||||
</td>
|
</td>
|
||||||
<td>
|
<td>
|
||||||
<div id="roll_slider" class="slider"></div>
|
<div id="board_roll_slider" class="slider"></div>
|
||||||
</td>
|
</td>
|
||||||
<td>
|
<td>
|
||||||
<input type="number" id="alignRoll" class="tab-magnetometer" data-setting="tz_offset"
|
<input type="number" id="boardAlignRoll" class="tab-magnetometer" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-180" max="360" />
|
||||||
data-setting-multiplier="1"
|
</td>
|
||||||
step="1" min="-180" max="180"/>
|
</tr>
|
||||||
</td>
|
<tr>
|
||||||
</tr>
|
<td class="info">
|
||||||
<tr>
|
<p class="title" data-i18n="configurationSensorAlignmentMagPitch" style="margin: 5px"></p>
|
||||||
<td class="info">
|
</td>
|
||||||
<p class="title" data-i18n="configurationSensorAlignmentMagRoll"></p>
|
<td>
|
||||||
</td>
|
<div id="board_pitch_slider" class="slider"></div>
|
||||||
<td>
|
</td>
|
||||||
<div id="pitch_slider" class="slider"></div>
|
<td>
|
||||||
</td>
|
<input type="number" id="boardAlignPitch" class="tab-magnetometer" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-180" max="360" />
|
||||||
<td>
|
</td>
|
||||||
<input type="number" id="alignPitch" class="tab-magnetometer" data-setting="tz_offset"
|
</tr>
|
||||||
data-setting-multiplier="1"
|
<tr>
|
||||||
step="1" min="-180" max="180"/>
|
<td class="info">
|
||||||
</td>
|
<p class="title" data-i18n="configurationSensorAlignmentMagYaw"></p>
|
||||||
</tr>
|
</td>
|
||||||
<tr>
|
<td>
|
||||||
<td class="info">
|
<div id="board_yaw_slider" class="slider"></div>
|
||||||
<p class="title" data-i18n="configurationSensorAlignmentMagYaw"></p>
|
</td>
|
||||||
</td>
|
<td>
|
||||||
<td>
|
<input type="number" id="boardAlignYaw" class="tab-magnetometer" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-180" max="360" />
|
||||||
<div id="yaw_slider" class="slider"></div>
|
</td>
|
||||||
</td>
|
</tr>
|
||||||
<td>
|
</tbody>
|
||||||
<input type="number" id="alignYaw" class="tab-magnetometer" data-setting="tz_offset"
|
</table>
|
||||||
data-setting-multiplier="1"
|
</div>
|
||||||
step="1" min="-180" max="360"/>
|
</div>
|
||||||
</td>
|
|
||||||
</tr>
|
<div class="config-section gui_box grey">
|
||||||
</tbody>
|
<div class="spacer_box">
|
||||||
</table>
|
<div id="alignment-info" class="info-box">
|
||||||
|
<span data-i18n="magnetometerInfo"></span>
|
||||||
|
</div>
|
||||||
|
<div class="select" style="display: flex; justify-content: left;">
|
||||||
|
<select id="magalign" class="magalign">
|
||||||
|
<option value="0">Default</option>
|
||||||
|
<!-- list generated here -->
|
||||||
|
</select>
|
||||||
|
<label for="magalign" data-i18n="magnetometerOrientationPreset"></label>
|
||||||
|
</div>
|
||||||
|
<div class="select" style="display: flex; justify-content: left;">
|
||||||
|
<select id="element_to_show">
|
||||||
|
<option value="0" selected>Magnetometer</option>
|
||||||
|
<option value="1">XYZ</option>
|
||||||
|
<!-- list generated here -->
|
||||||
|
</select>
|
||||||
|
<label for="element_to_show" data-i18n="magnetometerElementToShow"></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<table class="axis-table">
|
||||||
|
<thead>
|
||||||
|
<tr>
|
||||||
|
<td style="width: 5%; padding-bottom: 10px;">
|
||||||
|
<p class="table-title">
|
||||||
|
<span data-i18n="axisTableTitleAxis"></span>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td style="width: 90%; padding-bottom: 10px;">
|
||||||
|
<p class="table-title">
|
||||||
|
<span data-i18n="axisTableTitleSlider"></span>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td style="width: 5%; padding-bottom: 10px;">
|
||||||
|
<a class="table-title">
|
||||||
|
<span data-i18n="axisTableTitleValue"></span>
|
||||||
|
</a>
|
||||||
|
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</thead>
|
||||||
|
<tbody>
|
||||||
|
<tr>
|
||||||
|
<td class="info">
|
||||||
|
<p class="title" data-i18n="configurationSensorAlignmentMagRoll"></p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<div id="roll_slider" class="slider"></div>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<input type="number" id="alignRoll" class="tab-magnetometer" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-180" max="360" />
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td class="info">
|
||||||
|
<p class="title" data-i18n="configurationSensorAlignmentMagPitch" style="margin: 5px"></p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<div id="pitch_slider" class="slider"></div>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<input type="number" id="alignPitch" class="tab-magnetometer" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-180" max="360" />
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td class="info">
|
||||||
|
<p class="title" data-i18n="configurationSensorAlignmentMagYaw"></p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<div id="yaw_slider" class="slider"></div>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<input type="number" id="alignYaw" class="tab-magnetometer" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-180" max="360" />
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</tbody>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_toolbar">
|
<div class="clear-both"></div>
|
||||||
<div class="btn save_btn">
|
</div>
|
||||||
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
<div class="content_toolbar supported hide">
|
||||||
</div>
|
<div class="btn save_btn">
|
||||||
|
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="tab-auxiliary-templates">
|
<div id="tab-auxiliary-templates">
|
||||||
<table class="modes">
|
<table class="modes">
|
||||||
<tbody>
|
<tbody>
|
||||||
<tr class="mode">
|
<tr class="mode">
|
||||||
<td class="info">
|
<td class="info">
|
||||||
<p class="name"></p>
|
<p class="name"></p>
|
||||||
<div class="buttons">
|
<div class="buttons">
|
||||||
<a class="addRange" href="#" i18n="auxiliaryAddRange"></a>
|
<a class="addRange" href="#" i18n="auxiliaryAddRange"></a>
|
||||||
</div>
|
</div>
|
||||||
</td>
|
</td>
|
||||||
<td class="ranges"></td>
|
<td class="ranges"></td>
|
||||||
</tr>
|
</tr>
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
<div class="range">
|
<div class="range">
|
||||||
|
@ -150,8 +223,10 @@
|
||||||
<table>
|
<table>
|
||||||
<tr class="modeSection">
|
<tr class="modeSection">
|
||||||
<td colspan="2">
|
<td colspan="2">
|
||||||
<div class="modeSectionArea"><p class="modeSectionName"></p></div>
|
<div class="modeSectionArea">
|
||||||
|
<p class="modeSectionName"></p>
|
||||||
|
</div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
|
@ -1,5 +1,5 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
/*global chrome,GUI,TABS,nwdialog,$*/
|
/*global chrome,GUI,BOARD_ALIGNMENT,TABS,nwdialog,helper,$*/
|
||||||
|
|
||||||
TABS.magnetometer = {};
|
TABS.magnetometer = {};
|
||||||
|
|
||||||
|
@ -18,6 +18,12 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
yaw: 0
|
yaw: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.boardAlignmentConfig = {
|
||||||
|
pitch: 0,
|
||||||
|
roll: 0,
|
||||||
|
yaw: 0
|
||||||
|
};
|
||||||
|
|
||||||
self.pageElements = {};
|
self.pageElements = {};
|
||||||
self.isSavePreset = true;
|
self.isSavePreset = true;
|
||||||
self.showMagnetometer = true;
|
self.showMagnetometer = true;
|
||||||
|
@ -28,6 +34,13 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
|
|
||||||
var loadChain = [
|
var loadChain = [
|
||||||
mspHelper.loadMixerConfig,
|
mspHelper.loadMixerConfig,
|
||||||
|
mspHelper.loadBoardAlignment,
|
||||||
|
function (callback) {
|
||||||
|
self.boardAlignmentConfig.pitch = Math.round(BOARD_ALIGNMENT.pitch / 10);
|
||||||
|
self.boardAlignmentConfig.roll = Math.round(BOARD_ALIGNMENT.roll / 10);
|
||||||
|
self.boardAlignmentConfig.yaw = Math.round(BOARD_ALIGNMENT.yaw / 10);
|
||||||
|
callback();
|
||||||
|
},
|
||||||
mspHelper.loadSensorAlignment,
|
mspHelper.loadSensorAlignment,
|
||||||
// Pitch and roll must be inverted
|
// Pitch and roll must be inverted
|
||||||
function (callback) {
|
function (callback) {
|
||||||
|
@ -37,7 +50,7 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
},
|
},
|
||||||
function (callback) {
|
function (callback) {
|
||||||
mspHelper.getSetting("align_mag_pitch").then(function (data) {
|
mspHelper.getSetting("align_mag_pitch").then(function (data) {
|
||||||
self.alignmentConfig.pitch = (parseInt(data.value, 10) / 10) - 180;
|
self.alignmentConfig.pitch = parseInt(data.value, 10) / 10;
|
||||||
}).then(callback)
|
}).then(callback)
|
||||||
},
|
},
|
||||||
function (callback) {
|
function (callback) {
|
||||||
|
@ -51,12 +64,27 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
loadChainer.setExitPoint(load_html);
|
loadChainer.setExitPoint(load_html);
|
||||||
loadChainer.execute();
|
loadChainer.execute();
|
||||||
|
|
||||||
|
function areAnglesZero() {
|
||||||
|
return self.alignmentConfig.pitch === 0 && self.alignmentConfig.roll === 0 && self.alignmentConfig.yaw === 0
|
||||||
|
}
|
||||||
|
|
||||||
|
function isBoardAlignmentZero() {
|
||||||
|
return (self.boardAlignmentConfig.pitch == 0 ) && (self.boardAlignmentConfig.roll == 0 ) && (self.boardAlignmentConfig.yaw == 0);
|
||||||
|
}
|
||||||
|
|
||||||
//========================
|
//========================
|
||||||
// Save chain
|
// Save chain
|
||||||
// =======================
|
// =======================
|
||||||
var saveChainer = new MSPChainerClass();
|
var saveChainer = new MSPChainerClass();
|
||||||
|
|
||||||
var saveChain = [
|
var saveChain = [
|
||||||
|
function (callback) {
|
||||||
|
BOARD_ALIGNMENT.pitch = self.boardAlignmentConfig.pitch * 10;
|
||||||
|
BOARD_ALIGNMENT.roll = self.boardAlignmentConfig.roll * 10;
|
||||||
|
BOARD_ALIGNMENT.yaw = self.boardAlignmentConfig.yaw * 10;
|
||||||
|
callback();
|
||||||
|
},
|
||||||
|
mspHelper.saveBoardAlignment,
|
||||||
// Magnetometer alignment
|
// Magnetometer alignment
|
||||||
function (callback) {
|
function (callback) {
|
||||||
let orientation_mag_e = $('select.magalign');
|
let orientation_mag_e = $('select.magalign');
|
||||||
|
@ -65,7 +93,7 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
},
|
},
|
||||||
mspHelper.saveSensorAlignment,
|
mspHelper.saveSensorAlignment,
|
||||||
// Pitch/Roll/Yaw
|
// Pitch/Roll/Yaw
|
||||||
// Pitch and roll must be inverted
|
// Pitch and roll must be inverted - ???
|
||||||
function (callback) {
|
function (callback) {
|
||||||
if (self.isSavePreset)
|
if (self.isSavePreset)
|
||||||
mspHelper.setSetting("align_mag_roll", 0, callback);
|
mspHelper.setSetting("align_mag_roll", 0, callback);
|
||||||
|
@ -76,14 +104,19 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
if (self.isSavePreset)
|
if (self.isSavePreset)
|
||||||
mspHelper.setSetting("align_mag_pitch", 0, callback);
|
mspHelper.setSetting("align_mag_pitch", 0, callback);
|
||||||
else
|
else
|
||||||
mspHelper.setSetting("align_mag_pitch", (180 + self.alignmentConfig.pitch) * 10, callback);
|
mspHelper.setSetting("align_mag_pitch", self.alignmentConfig.pitch * 10, callback);
|
||||||
|
|
||||||
},
|
},
|
||||||
function (callback) {
|
function (callback) {
|
||||||
if (self.isSavePreset)
|
if (self.isSavePreset)
|
||||||
mspHelper.setSetting("align_mag_yaw", 0, callback);
|
mspHelper.setSetting("align_mag_yaw", 0, callback);
|
||||||
else
|
else {
|
||||||
mspHelper.setSetting("align_mag_yaw", self.alignmentConfig.yaw * 10, callback);
|
var fix = 0;
|
||||||
|
if ( areAnglesZero() ) {
|
||||||
|
fix = 1; //if all angles are 0, then we have to save yaw = 1 (0.1 deg) to enforce usage of angles, not a usage of preset
|
||||||
|
}
|
||||||
|
mspHelper.setSetting("align_mag_yaw", self.alignmentConfig.yaw * 10 + fix, callback);
|
||||||
|
}
|
||||||
},
|
},
|
||||||
mspHelper.saveToEeprom
|
mspHelper.saveToEeprom
|
||||||
];
|
];
|
||||||
|
@ -117,35 +150,98 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
return arr;
|
return arr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function toUpperRange(input, max) {
|
||||||
|
while (input > max) input -= 360;
|
||||||
|
while (input + 360 <= max) input += 360;
|
||||||
|
return input;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Returns pitch, roll and yaw in degree by the id of a preset.
|
Returns pitch, roll and yaw in degree by the id of a preset.
|
||||||
Degree are the ones used in the slider
|
Degree are the ones used in the slider
|
||||||
*/
|
*/
|
||||||
function getAxisDegreeWithPreset(selectedPreset) {
|
function getAxisDegreeWithPreset(selectedPreset) {
|
||||||
|
//pitch, roll, yaw
|
||||||
switch (selectedPreset) {
|
switch (selectedPreset) {
|
||||||
case 1: //CW0_DEG = 1
|
case 1: //CW0_DEG = 1
|
||||||
return [180, 0, 0];
|
|
||||||
case 2: //CW90_DEG = 2
|
|
||||||
return [180, 0, 90];
|
|
||||||
case 3: //CW180_DEG = 3
|
|
||||||
return [180, 0, 180];
|
|
||||||
case 4: //CW270_DEG = 4
|
|
||||||
return [180, 0, 270];
|
|
||||||
case 5: //CW0_DEG_FLIP = 5
|
|
||||||
return [0, 0, 0];
|
return [0, 0, 0];
|
||||||
case 6: //CW90_DEG_FLIP = 5
|
case 2: //CW90_DEG = 2
|
||||||
return [0, 0, 90];
|
return [0, 0, 90];
|
||||||
case 7: //CW180_DEG_FLIP = 5
|
case 3: //CW180_DEG = 3
|
||||||
return [0, 0, 180];
|
return [0, 0, 180];
|
||||||
|
case 4: //CW270_DEG = 4
|
||||||
|
return [0, 0, 270];
|
||||||
|
case 5: //CW0_DEG_FLIP = 5
|
||||||
|
return [180, 0, 0];
|
||||||
|
case 6: //CW90_DEG_FLIP = 5
|
||||||
|
return [180, 0, 90];
|
||||||
|
case 7: //CW180_DEG_FLIP = 5
|
||||||
|
return [180, 0, 180];
|
||||||
case 0: //ALIGN_DEFAULT = 0
|
case 0: //ALIGN_DEFAULT = 0
|
||||||
case 8: //CW270_DEG_FLIP = 5
|
case 8: //CW270_DEG_FLIP = 5
|
||||||
default://If not recognized, returns defualt
|
default://If not recognized, returns defualt
|
||||||
return [0, 0, 270];
|
return [180, 0, 270];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function isUsingAPreset() {
|
function getAxisDegreeWithPresetAndBoardOrientation(selectedPreset) {
|
||||||
return self.alignmentConfig.pitch === -180 && self.alignmentConfig.roll === 0 && self.alignmentConfig.yaw === 0
|
var degree = getAxisDegreeWithPreset(selectedPreset);
|
||||||
|
|
||||||
|
if (isBoardAlignmentZero()) {
|
||||||
|
return degree;
|
||||||
|
}
|
||||||
|
|
||||||
|
//degree[0] - pitch
|
||||||
|
//degree[1] - roll
|
||||||
|
//degree[2] - yaw
|
||||||
|
//-(pitch-180), -180 - yaw, roll
|
||||||
|
var magRotation = new THREE.Euler(-THREE.Math.degToRad(degree[0]-180), THREE.Math.degToRad(-180 - degree[2]), THREE.Math.degToRad(degree[1]), 'YXZ');
|
||||||
|
var matrix = (new THREE.Matrix4()).makeRotationFromEuler(magRotation);
|
||||||
|
|
||||||
|
var boardRotation = new THREE.Euler( THREE.Math.degToRad( -self.boardAlignmentConfig.pitch ), THREE.Math.degToRad( -self.boardAlignmentConfig.yaw ), THREE.Math.degToRad( -self.boardAlignmentConfig.roll ), 'YXZ');
|
||||||
|
var matrix1 = (new THREE.Matrix4()).makeRotationFromEuler(boardRotation);
|
||||||
|
|
||||||
|
matrix.premultiply(matrix1);
|
||||||
|
|
||||||
|
var euler = new THREE.Euler();
|
||||||
|
euler.setFromRotationMatrix(matrix, 'YXZ');
|
||||||
|
|
||||||
|
var pitch = toUpperRange( Math.round( THREE.Math.radToDeg(-euler.x)) + 180, 180 );
|
||||||
|
var yaw = toUpperRange( Math.round( -180 - THREE.Math.radToDeg(euler.y)), 359 );
|
||||||
|
var roll = toUpperRange( Math.round( THREE.Math.radToDeg(euler.z)), 180 );
|
||||||
|
|
||||||
|
return [pitch, roll, yaw];
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateMagOrientationWithPreset() {
|
||||||
|
if (self.isSavePreset) {
|
||||||
|
const degrees = getAxisDegreeWithPresetAndBoardOrientation(SENSOR_ALIGNMENT.align_mag);
|
||||||
|
presetUpdated(degrees);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateBoardRollAxis(value) {
|
||||||
|
self.boardAlignmentConfig.roll = Number(value);
|
||||||
|
self.pageElements.board_roll_slider.val(self.boardAlignmentConfig.roll);
|
||||||
|
self.pageElements.orientation_board_roll.val(self.boardAlignmentConfig.roll);
|
||||||
|
updateMagOrientationWithPreset();
|
||||||
|
self.render3D();
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateBoardPitchAxis(value) {
|
||||||
|
self.boardAlignmentConfig.pitch = Number(value);
|
||||||
|
self.pageElements.board_pitch_slider.val(self.boardAlignmentConfig.pitch);
|
||||||
|
self.pageElements.orientation_board_pitch.val(self.boardAlignmentConfig.pitch);
|
||||||
|
updateMagOrientationWithPreset();
|
||||||
|
self.render3D();
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateBoardYawAxis(value) {
|
||||||
|
self.boardAlignmentConfig.yaw = Number(value);
|
||||||
|
self.pageElements.board_yaw_slider.val(self.boardAlignmentConfig.yaw);
|
||||||
|
self.pageElements.orientation_board_yaw.val(self.boardAlignmentConfig.yaw);
|
||||||
|
updateMagOrientationWithPreset();
|
||||||
|
self.render3D();
|
||||||
}
|
}
|
||||||
|
|
||||||
//Called when roll values change
|
//Called when roll values change
|
||||||
|
@ -172,10 +268,22 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
self.render3D();
|
self.render3D();
|
||||||
}
|
}
|
||||||
|
|
||||||
//Called when a preset is selected
|
function enableSavePreset() {
|
||||||
function presetUpdated(degrees) {
|
|
||||||
self.isSavePreset = true;
|
self.isSavePreset = true;
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 1);
|
self.pageElements.orientation_mag_e.css("opacity", 1);
|
||||||
|
self.pageElements.orientation_mag_e.css("text-decoration", "");
|
||||||
|
}
|
||||||
|
|
||||||
|
function disableSavePreset() {
|
||||||
|
self.isSavePreset = false;
|
||||||
|
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
||||||
|
self.pageElements.orientation_mag_e.css("text-decoration", "line-through");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//Called when a preset is selected
|
||||||
|
function presetUpdated(degrees) {
|
||||||
|
enableSavePreset();
|
||||||
updatePitchAxis(degrees[0]);
|
updatePitchAxis(degrees[0]);
|
||||||
updateRollAxis(degrees[1]);
|
updateRollAxis(degrees[1]);
|
||||||
updateYawAxis(degrees[2]);
|
updateYawAxis(degrees[2]);
|
||||||
|
@ -183,12 +291,21 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
|
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
|
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
// initialize 3D
|
// initialize 3D
|
||||||
self.initialize3D();
|
self.initialize3D();
|
||||||
|
|
||||||
let alignments = FC.getSensorAlignments();
|
let alignments = FC.getSensorAlignments();
|
||||||
|
|
||||||
|
self.pageElements.orientation_board_roll = $('#boardAlignRoll');
|
||||||
|
self.pageElements.orientation_board_pitch = $('#boardAlignPitch');
|
||||||
|
self.pageElements.orientation_board_yaw = $('#boardAlignYaw');
|
||||||
|
self.pageElements.board_roll_slider = $('#board_roll_slider');
|
||||||
|
self.pageElements.board_pitch_slider = $('#board_pitch_slider');
|
||||||
|
self.pageElements.board_yaw_slider = $('#board_yaw_slider');
|
||||||
|
|
||||||
self.pageElements.orientation_mag_e = $('select.magalign');
|
self.pageElements.orientation_mag_e = $('select.magalign');
|
||||||
self.pageElements.orientation_mag_roll = $('#alignRoll');
|
self.pageElements.orientation_mag_roll = $('#alignRoll');
|
||||||
self.pageElements.orientation_mag_pitch = $('#alignPitch');
|
self.pageElements.orientation_mag_pitch = $('#alignPitch');
|
||||||
|
@ -197,28 +314,102 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
self.pageElements.pitch_slider = $('#pitch_slider');
|
self.pageElements.pitch_slider = $('#pitch_slider');
|
||||||
self.pageElements.yaw_slider = $('#yaw_slider');
|
self.pageElements.yaw_slider = $('#yaw_slider');
|
||||||
|
|
||||||
|
self.roll_e = $('dd.roll'),
|
||||||
|
self.pitch_e = $('dd.pitch'),
|
||||||
|
self.heading_e = $('dd.heading');
|
||||||
|
|
||||||
for (i = 0; i < alignments.length; i++) {
|
for (i = 0; i < alignments.length; i++) {
|
||||||
self.pageElements.orientation_mag_e.append('<option value="' + (i + 1) + '">' + alignments[i] + '</option>');
|
self.pageElements.orientation_mag_e.append('<option value="' + (i + 1) + '">' + alignments[i] + '</option>');
|
||||||
}
|
}
|
||||||
self.pageElements.orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
self.pageElements.orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
||||||
|
|
||||||
if (isUsingAPreset()) {
|
if (areAnglesZero()) {
|
||||||
//If using a preset, checking if custom values are equal to 0
|
//If using a preset, checking if custom values are equal to 0
|
||||||
//Update the slider, but don't save the value until they will be not modified.
|
//Update the slider, but don't save the value until they will be not modified.
|
||||||
const degrees = getAxisDegreeWithPreset(SENSOR_ALIGNMENT.align_mag);
|
const degrees = getAxisDegreeWithPresetAndBoardOrientation(SENSOR_ALIGNMENT.align_mag);
|
||||||
presetUpdated(degrees);
|
presetUpdated(degrees);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
updateRollAxis(self.alignmentConfig.roll);
|
updateRollAxis(self.alignmentConfig.roll);
|
||||||
updatePitchAxis(self.alignmentConfig.pitch);
|
updatePitchAxis(self.alignmentConfig.pitch);
|
||||||
updateYawAxis(self.alignmentConfig.yaw);
|
updateYawAxis(self.alignmentConfig.yaw);
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
disableSavePreset();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
self.pageElements.orientation_board_roll.change(function () {
|
||||||
|
updateBoardRollAxis(clamp(this, -180, 360));
|
||||||
|
});
|
||||||
|
|
||||||
|
self.pageElements.orientation_board_pitch.change(function () {
|
||||||
|
updateBoardPitchAxis(clamp(this, -180, 360));
|
||||||
|
});
|
||||||
|
|
||||||
|
self.pageElements.orientation_board_yaw.change(function () {
|
||||||
|
updateBoardYawAxis(clamp(this, -180, 360));
|
||||||
|
});
|
||||||
|
|
||||||
|
self.pageElements.board_roll_slider.noUiSlider({
|
||||||
|
start: [self.boardAlignmentConfig.roll],
|
||||||
|
range: {
|
||||||
|
'min': [-180],
|
||||||
|
'max': [360]
|
||||||
|
},
|
||||||
|
step: 1,
|
||||||
|
});
|
||||||
|
self.pageElements.board_roll_slider.noUiSlider_pips({
|
||||||
|
mode: 'values',
|
||||||
|
values: generateRange(-180, 360, 45),
|
||||||
|
density: 4,
|
||||||
|
stepped: true
|
||||||
|
});
|
||||||
|
|
||||||
|
self.pageElements.board_pitch_slider.noUiSlider({
|
||||||
|
start: [self.boardAlignmentConfig.pitch],
|
||||||
|
range: {
|
||||||
|
'min': [-180],
|
||||||
|
'max': [360]
|
||||||
|
},
|
||||||
|
step: 1,
|
||||||
|
});
|
||||||
|
self.pageElements.board_pitch_slider.noUiSlider_pips({
|
||||||
|
mode: 'values',
|
||||||
|
values: generateRange(-180, 360, 45),
|
||||||
|
density: 4,
|
||||||
|
stepped: true
|
||||||
|
});
|
||||||
|
|
||||||
|
self.pageElements.board_yaw_slider.noUiSlider({
|
||||||
|
start: [self.boardAlignmentConfig.yaw],
|
||||||
|
range: {
|
||||||
|
'min': [-180],
|
||||||
|
'max': [360]
|
||||||
|
},
|
||||||
|
step: 1,
|
||||||
|
});
|
||||||
|
self.pageElements.board_yaw_slider.noUiSlider_pips({
|
||||||
|
mode: 'values',
|
||||||
|
values: generateRange(-180, 360, 45),
|
||||||
|
density: 4,
|
||||||
|
stepped: true
|
||||||
|
});
|
||||||
|
|
||||||
|
|
||||||
|
self.pageElements.board_pitch_slider.Link('lower').to((e) => {
|
||||||
|
updateBoardPitchAxis(e);
|
||||||
|
});
|
||||||
|
self.pageElements.board_roll_slider.Link('lower').to((e) => {
|
||||||
|
updateBoardRollAxis(e);
|
||||||
|
});
|
||||||
|
self.pageElements.board_yaw_slider.Link('lower').to((e) => {
|
||||||
|
updateBoardYawAxis(e);
|
||||||
|
});
|
||||||
|
|
||||||
const elementToShow = $("#element_to_show");
|
const elementToShow = $("#element_to_show");
|
||||||
elementToShow.change(function () {
|
elementToShow.change(function () {
|
||||||
const value = parseInt($(this).val());
|
const value = parseInt($(this).val());
|
||||||
self.showMagnetometer = (value == 0);
|
self.showMagnetometer = (value == 0);
|
||||||
|
self.render3D();
|
||||||
});
|
});
|
||||||
|
|
||||||
function clamp(input, min, max) {
|
function clamp(input, min, max) {
|
||||||
|
@ -227,28 +418,28 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
|
|
||||||
self.pageElements.orientation_mag_e.change(function () {
|
self.pageElements.orientation_mag_e.change(function () {
|
||||||
SENSOR_ALIGNMENT.align_mag = parseInt($(this).val());
|
SENSOR_ALIGNMENT.align_mag = parseInt($(this).val());
|
||||||
const degrees = getAxisDegreeWithPreset(SENSOR_ALIGNMENT.align_mag);
|
const degrees = getAxisDegreeWithPresetAndBoardOrientation(SENSOR_ALIGNMENT.align_mag);
|
||||||
|
presetUpdated(degrees);
|
||||||
|
});
|
||||||
|
|
||||||
|
self.pageElements.orientation_mag_e.on('mousedown', function () {
|
||||||
|
const degrees = getAxisDegreeWithPresetAndBoardOrientation(SENSOR_ALIGNMENT.align_mag);
|
||||||
presetUpdated(degrees);
|
presetUpdated(degrees);
|
||||||
});
|
});
|
||||||
|
|
||||||
self.pageElements.orientation_mag_roll.change(function () {
|
self.pageElements.orientation_mag_roll.change(function () {
|
||||||
self.isSavePreset = false;
|
disableSavePreset();
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
updateRollAxis(clamp(this, -180, 360));
|
||||||
updateRollAxis(clamp(this, -180, 180));
|
|
||||||
});
|
});
|
||||||
|
|
||||||
self.pageElements.orientation_mag_pitch.change(function () {
|
self.pageElements.orientation_mag_pitch.change(function () {
|
||||||
self.isSavePreset = false;
|
disableSavePreset();
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
updatePitchAxis(clamp(this, -180, 360));
|
||||||
updatePitchAxis(clamp(this, -180, 180));
|
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
self.pageElements.orientation_mag_yaw.change(function () {
|
self.pageElements.orientation_mag_yaw.change(function () {
|
||||||
self.isSavePreset = false;
|
disableSavePreset();
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
|
||||||
updateYawAxis(clamp(this, -180, 360));
|
updateYawAxis(clamp(this, -180, 360));
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
|
@ -259,13 +450,13 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
start: [self.alignmentConfig.roll],
|
start: [self.alignmentConfig.roll],
|
||||||
range: {
|
range: {
|
||||||
'min': [-180],
|
'min': [-180],
|
||||||
'max': [180]
|
'max': [360]
|
||||||
},
|
},
|
||||||
step: 1,
|
step: 1,
|
||||||
});
|
});
|
||||||
self.pageElements.roll_slider.noUiSlider_pips({
|
self.pageElements.roll_slider.noUiSlider_pips({
|
||||||
mode: 'values',
|
mode: 'values',
|
||||||
values: generateRange(-180, 180, 15),
|
values: generateRange(-180, 360, 45),
|
||||||
density: 4,
|
density: 4,
|
||||||
stepped: true
|
stepped: true
|
||||||
});
|
});
|
||||||
|
@ -274,13 +465,13 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
start: [self.alignmentConfig.pitch],
|
start: [self.alignmentConfig.pitch],
|
||||||
range: {
|
range: {
|
||||||
'min': [-180],
|
'min': [-180],
|
||||||
'max': [180]
|
'max': [360]
|
||||||
},
|
},
|
||||||
step: 1,
|
step: 1,
|
||||||
});
|
});
|
||||||
self.pageElements.pitch_slider.noUiSlider_pips({
|
self.pageElements.pitch_slider.noUiSlider_pips({
|
||||||
mode: 'values',
|
mode: 'values',
|
||||||
values: generateRange(-180, 180, 15),
|
values: generateRange(-180, 360, 45),
|
||||||
density: 4,
|
density: 4,
|
||||||
stepped: true
|
stepped: true
|
||||||
});
|
});
|
||||||
|
@ -291,7 +482,7 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
'min': [-180],
|
'min': [-180],
|
||||||
'max': [360]
|
'max': [360]
|
||||||
},
|
},
|
||||||
step: 45,
|
step: 1,
|
||||||
});
|
});
|
||||||
self.pageElements.yaw_slider.noUiSlider_pips({
|
self.pageElements.yaw_slider.noUiSlider_pips({
|
||||||
mode: 'values',
|
mode: 'values',
|
||||||
|
@ -300,6 +491,7 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
stepped: true
|
stepped: true
|
||||||
});
|
});
|
||||||
|
|
||||||
|
|
||||||
self.pageElements.pitch_slider.Link('lower').to((e) => {
|
self.pageElements.pitch_slider.Link('lower').to((e) => {
|
||||||
updatePitchAxis(e);
|
updatePitchAxis(e);
|
||||||
});
|
});
|
||||||
|
@ -310,19 +502,31 @@ TABS.magnetometer.initialize = function (callback) {
|
||||||
updateYawAxis(e);
|
updateYawAxis(e);
|
||||||
});
|
});
|
||||||
|
|
||||||
self.pageElements.pitch_slider.change((e) => {
|
self.pageElements.pitch_slider.on('slide', (e) => {
|
||||||
self.isSavePreset = false;
|
disableSavePreset();
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
|
||||||
});
|
});
|
||||||
self.pageElements.roll_slider.change((e) => {
|
self.pageElements.roll_slider.on('slide', (e) => {
|
||||||
self.isSavePreset = false;
|
disableSavePreset();
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
|
||||||
});
|
});
|
||||||
self.pageElements.yaw_slider.change((e) => {
|
self.pageElements.yaw_slider.on('slide', (e) => {
|
||||||
self.isSavePreset = false;
|
disableSavePreset();
|
||||||
self.pageElements.orientation_mag_e.css("opacity", 0.5);
|
|
||||||
});
|
});
|
||||||
|
|
||||||
|
function get_fast_data() {
|
||||||
|
if (helper.mspQueue.shouldDrop()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
MSP.send_message(MSPCodes.MSP_ATTITUDE, false, false, function () {
|
||||||
|
self.roll_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[0]]));
|
||||||
|
self.pitch_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[1]]));
|
||||||
|
self.heading_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[2]]));
|
||||||
|
self.render3D();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
helper.mspBalancedInterval.add('setup_data_pull_fast', 40, 1, get_fast_data);
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -341,6 +545,7 @@ TABS.magnetometer.initialize3D = function () {
|
||||||
scene,
|
scene,
|
||||||
gps,
|
gps,
|
||||||
xyz,
|
xyz,
|
||||||
|
fc,
|
||||||
useWebGlRenderer = false;
|
useWebGlRenderer = false;
|
||||||
|
|
||||||
canvas = $('.model-and-info #canvas');
|
canvas = $('.model-and-info #canvas');
|
||||||
|
@ -385,13 +590,27 @@ TABS.magnetometer.initialize3D = function () {
|
||||||
|
|
||||||
this.render3D = function () {
|
this.render3D = function () {
|
||||||
|
|
||||||
if (!gps || !xyz)
|
if (!gps || !xyz || !fc)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
gps.visible = self.showMagnetometer;
|
gps.visible = self.showMagnetometer;
|
||||||
xyz.visible = !self.showMagnetometer;
|
xyz.visible = !self.showMagnetometer;
|
||||||
gps.rotation.set(-THREE.Math.degToRad(self.alignmentConfig.pitch), THREE.Math.degToRad(-180 - self.alignmentConfig.yaw), THREE.Math.degToRad(self.alignmentConfig.roll), 'YXZ');
|
fc.visible = true;
|
||||||
xyz.rotation.set(-THREE.Math.degToRad(self.alignmentConfig.pitch), THREE.Math.degToRad(-180 - self.alignmentConfig.yaw), THREE.Math.degToRad(self.alignmentConfig.roll), 'YXZ');
|
|
||||||
|
var magRotation = new THREE.Euler(-THREE.Math.degToRad(self.alignmentConfig.pitch-180), THREE.Math.degToRad(-180 - self.alignmentConfig.yaw), THREE.Math.degToRad(self.alignmentConfig.roll), 'YXZ');
|
||||||
|
var matrix = (new THREE.Matrix4()).makeRotationFromEuler(magRotation);
|
||||||
|
|
||||||
|
var boardRotation = new THREE.Euler( THREE.Math.degToRad( -self.boardAlignmentConfig.pitch ), THREE.Math.degToRad( -self.boardAlignmentConfig.yaw ), THREE.Math.degToRad( -self.boardAlignmentConfig.roll ), 'YXZ');
|
||||||
|
var matrix1 = (new THREE.Matrix4()).makeRotationFromEuler(boardRotation);
|
||||||
|
|
||||||
|
/*
|
||||||
|
if ( self.isSavePreset ) {
|
||||||
|
matrix.premultiply(matrix1); //preset specifies orientation relative to FC, align_max_xxx specify absolute orientation
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
gps.rotation.setFromRotationMatrix(matrix);
|
||||||
|
xyz.rotation.setFromRotationMatrix(matrix);
|
||||||
|
fc.rotation.setFromRotationMatrix(matrix1);
|
||||||
|
|
||||||
// draw
|
// draw
|
||||||
if (camera != null)
|
if (camera != null)
|
||||||
|
@ -429,7 +648,7 @@ TABS.magnetometer.initialize3D = function () {
|
||||||
case "twin_plane":
|
case "twin_plane":
|
||||||
case "vtail_plane":
|
case "vtail_plane":
|
||||||
case "vtail_single_servo_plane":
|
case "vtail_single_servo_plane":
|
||||||
return [0, 1.4, 0];
|
return [0, 1.6, 0];
|
||||||
case "fallback":
|
case "fallback":
|
||||||
default:
|
default:
|
||||||
return [0, 2.5, 0];
|
return [0, 2.5, 0];
|
||||||
|
@ -479,7 +698,7 @@ TABS.magnetometer.initialize3D = function () {
|
||||||
gps = obj.scene;
|
gps = obj.scene;
|
||||||
const scaleFactor = 0.04;
|
const scaleFactor = 0.04;
|
||||||
gps.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
gps.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
||||||
gps.position.set(gpsOffset[0], gpsOffset[1], gpsOffset[2]);
|
gps.position.set(gpsOffset[0], gpsOffset[1] + 0.5, gpsOffset[2]);
|
||||||
gps.traverse(child => {
|
gps.traverse(child => {
|
||||||
if (child.material) child.material.metalness = 0;
|
if (child.material) child.material.metalness = 0;
|
||||||
});
|
});
|
||||||
|
@ -493,11 +712,23 @@ TABS.magnetometer.initialize3D = function () {
|
||||||
xyz = obj.scene;
|
xyz = obj.scene;
|
||||||
const scaleFactor = 0.04;
|
const scaleFactor = 0.04;
|
||||||
xyz.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
xyz.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
||||||
xyz.position.set(gpsOffset[0], gpsOffset[1], gpsOffset[2]);
|
xyz.position.set(gpsOffset[0], gpsOffset[1] + 0.5, gpsOffset[2]);
|
||||||
xyz.rotation.y = 3 * Math.PI / 2;
|
xyz.rotation.y = 3 * Math.PI / 2;
|
||||||
model.add(xyz);
|
model.add(xyz);
|
||||||
this.render3D();
|
this.render3D();
|
||||||
});
|
});
|
||||||
|
|
||||||
|
//Load the FC model
|
||||||
|
loader.load('./resources/models/fc.gltf', (obj) => {
|
||||||
|
fc = obj.scene;
|
||||||
|
const scaleFactor = 0.04;
|
||||||
|
fc.scale.set(scaleFactor, scaleFactor, scaleFactor);
|
||||||
|
fc.position.set(gpsOffset[0], gpsOffset[1] - 0.5, gpsOffset[2]);
|
||||||
|
fc.rotation.y = 3 * Math.PI / 2;
|
||||||
|
model.add(fc);
|
||||||
|
this.render3D();
|
||||||
|
});
|
||||||
|
|
||||||
});
|
});
|
||||||
this.render3D();
|
this.render3D();
|
||||||
this.resize3D();
|
this.resize3D();
|
||||||
|
|
|
@ -1,28 +1,28 @@
|
||||||
<div class="tab-mission-control">
|
<div class="tab-mission-control">
|
||||||
<div style="padding-top: 20px;padding-left: 20px; padding-right: 20px;position: relative;">
|
<div style="padding-top: 20px;padding-left: 20px; padding-right: 20px;position: relative;">
|
||||||
<div class="tab_title" data-i18n="tabMissionControl">Mission planner</div>
|
<div class="tab_title" data-i18n="tabMissionControl"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="cf_column fourth" id="missionControls">
|
<div class="cf_column fourth" id="missionControls">
|
||||||
<div class="spacer_right">
|
<div class="spacer_right">
|
||||||
<div id="missionPlannerAction" class="gui_box grey">
|
<div id="missionPlannerAction" class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionActionMenuHead">Action Menu</div>
|
<div class="spacer_box_title" data-i18n="missionActionMenuHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon show_btn" id="showHideActionButton">
|
<div class="btnMenu btnMenuIcon show_btn" id="showHideActionButton">
|
||||||
<a class="ic_hide" href="#" title="Hide"></a>
|
<a class="ic_hide" href="#" i18n_title="missionTitleHide"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer" id="ActionContent">
|
<div class="spacer" id="ActionContent">
|
||||||
|
|
||||||
<div class="btn save_btn">
|
<div class="btn save_btn">
|
||||||
<a id="loadFileMissionButton" class="btnicon ic_loadFromFile" href="#" title="Load Mission File"></a>
|
<a id="loadFileMissionButton" class="btnicon ic_loadFromFile" href="#" i18n_title="missionTitleLoadMissionFile"></a>
|
||||||
<a id="saveFileMissionButton" class="btnicon ic_save2File" href="#" title="Save Mission File"></a>
|
<a id="saveFileMissionButton" class="btnicon ic_save2File" href="#" i18n_title="missionTitleSaveMissionFile"></a>
|
||||||
</div>
|
</div>
|
||||||
<div class="btn save_btn">
|
<div class="btn save_btn">
|
||||||
<a id="loadMissionButton" class="btnicon ic_loadFromFC" href="#" title="Load mission from FC"</a>
|
<a id="loadMissionButton" class="btnicon ic_loadFromFC" href="#" i18n_title="missionTitleLoadMissionFromFC" </a>
|
||||||
<a id="saveMissionButton" class="btnicon ic_save2FC" href="#" title="Save mission to FC"</a>
|
<a id="saveMissionButton" class="btnicon ic_save2FC" href="#" i18n_title="missionTitleSaveMissionToFC" </a>
|
||||||
<a id="loadEepromMissionButton" class="btnicon ic_loadFromEprom" href="#" title="Load Eeprom mission"></a>
|
<a id="loadEepromMissionButton" class="btnicon ic_loadFromEprom" href="#" i18n_title="missionTitleLoadEepromMission"></a>
|
||||||
<a id="saveEepromMissionButton" class="btnicon ic_save2Eprom" href="#" title="Save Eeprom mission"></a>
|
<a id="saveEepromMissionButton" class="btnicon ic_save2Eprom" href="#" i18n_title="missionTitleSaveEepromMission"></a>
|
||||||
</div>
|
</div>
|
||||||
<hr>
|
<hr>
|
||||||
<!-- <div class="btn">
|
<!-- <div class="btn">
|
||||||
|
@ -33,33 +33,33 @@
|
||||||
</div>
|
</div>
|
||||||
<hr> -->
|
<hr> -->
|
||||||
<div id="removeAllPoints" class="btn btn-danger" style="padding-top: 1px; display: inline-block">
|
<div id="removeAllPoints" class="btn btn-danger" style="padding-top: 1px; display: inline-block">
|
||||||
<a class="btnicon ic_removeAll" href="#" title="Remove all"></a>
|
<a class="btnicon ic_removeAll" href="#" i18n_title="missionTitleRemoveAll"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="missionPlannerTotalInfo" class="gui_box grey">
|
<div id="missionPlannerTotalInfo" class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionTotalInformationHead">Total information</div>
|
<div class="spacer_box_title" data-i18n="missionTotalInformationHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon show_btn" id="showHideInfoButton">
|
<div class="btnMenu btnMenuIcon show_btn" id="showHideInfoButton">
|
||||||
<a class="ic_hide" href="#" title="Hide"></a>
|
<a class="ic_hide" href="#" i18n_title="missionTitleHide"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer" id="InfoContent">
|
<div class="spacer" id="InfoContent">
|
||||||
<div id="infoMissionFilename" style="padding-bottom: 2px;">
|
<div id="infoMissionFilename" style="padding-bottom: 2px;">
|
||||||
<span>Filename loaded:</span>
|
<span data-i18n="missionTotalInfoFilenameLoaded"></span>
|
||||||
<span id="missionFilename" style="color: #3394b5"></span>
|
<span id="missionFilename" style="color: #3394b5"></span>
|
||||||
</div>
|
</div>
|
||||||
<div id="infoMissionDistance" style="padding-bottom: 2px;">
|
<div id="infoMissionDistance" style="padding-bottom: 2px;">
|
||||||
<span>Distance (m):</span>
|
<span data-i18n="missionTotalInfoDistance"></span>
|
||||||
<span id="missionDistance"></span>
|
<span id="missionDistance"></span>
|
||||||
</div>
|
</div>
|
||||||
<div id="infoAvailablePoints" style="padding-bottom: 2px;">
|
<div id="infoAvailablePoints" style="padding-bottom: 2px;">
|
||||||
<span>Available Points</span>
|
<span data-i18n="missionTotalInfoAvailablePoints"></span>
|
||||||
<span id="availablePoints">0/0</span>
|
<span id="availablePoints">0/0</span>
|
||||||
</div>
|
</div>
|
||||||
<div id="infoMissionValid" style="padding-bottom: 2px;">
|
<div id="infoMissionValid" style="padding-bottom: 2px;">
|
||||||
<span>Mission valid</span>
|
<span data-i18n="missionTotalInfoMissionValid"></span>
|
||||||
<div id="missionValid" style="display: inline-block"></div>
|
<div id="missionValid" style="display: inline-block"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -67,23 +67,23 @@
|
||||||
|
|
||||||
<div id="missionPlannerSettings" class="gui_box grey" style="display: none">
|
<div id="missionPlannerSettings" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionDefaultSettingsHead">Default settings</div>
|
<div class="spacer_box_title" data-i18n="missionDefaultSettingsHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
<a id="cancelSettings" class="ic_cancel" href="#" title="Cancel"></a>
|
<a id="cancelSettings" class="ic_cancel" href="#" i18n_title="missionTitleCancel"></a>
|
||||||
<a id="saveSettings" class="ic_save" href="#" title="Save"></a>
|
<a id="saveSettings" class="ic_save" href="#" i18n_title="missionTitleSave"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer">
|
<div class="spacer">
|
||||||
<div class="point">
|
<div class="point">
|
||||||
<label class="point-label" for="MPdefaultPointAlt">Alt (cm): </label>
|
<label class="point-label" for="MPdefaultPointAlt" data-i18n="missionDefaultPointAlt"></label>
|
||||||
<input id="MPdefaultPointAlt" type="text" value="0" required>
|
<input id="MPdefaultPointAlt" type="text" value="0" required>
|
||||||
</div>
|
</div>
|
||||||
<div class="point">
|
<div class="point">
|
||||||
<label class="point-label" for="MPdefaultPointSpeed">Speed (cm/s): </label>
|
<label class="point-label" for="MPdefaultPointSpeed" data-i18n="missionDefaultPointSpeed"></label>
|
||||||
<input id="MPdefaultPointSpeed" type="text" value="0" required>
|
<input id="MPdefaultPointSpeed" type="text" value="0" required>
|
||||||
</div>
|
</div>
|
||||||
<div class="point">
|
<div class="point">
|
||||||
<label class="point-label" for="MPdefaultSafeRangeSH">Radius (m): </label>
|
<label class="point-label" for="MPdefaultSafeRangeSH" data-i18n="missionDefaultSafeRangeSH"></label>
|
||||||
<input id="MPdefaultSafeRangeSH" type="text" value="0" required>
|
<input id="MPdefaultSafeRangeSH" type="text" value="0" required>
|
||||||
</div>
|
</div>
|
||||||
<div class="point">
|
<div class="point">
|
||||||
|
@ -99,38 +99,38 @@
|
||||||
|
|
||||||
<div id="missionPlannerMultiMission" class="gui_box grey" style="display: none">
|
<div id="missionPlannerMultiMission" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionMultiMissionHead">Multi Missions</div>
|
<div class="spacer_box_title" data-i18n="missionMultiMissionHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
<div id="showHideMultimissionButton">
|
<div id="showHideMultimissionButton">
|
||||||
<a class="ic_hide" href="#" title="Hide"></a>
|
<a class="ic_hide" href="#" i18n_title="missionTitleHide"></a>
|
||||||
</div>
|
</div>
|
||||||
<a id="cancelMultimission" class="ic_cancel" href="#" title="Cancel"></a>
|
<a id="cancelMultimission" class="ic_cancel" href="#" i18n_title="missionTitleCancel"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer" id="multimissionContent">
|
<div class="spacer" id="multimissionContent">
|
||||||
<div class="btn btnTable btnTableIcon save_btn">
|
<div class="btn btnTable btnTableIcon save_btn">
|
||||||
<div>
|
<div>
|
||||||
<span>Missions Info:</span>
|
<span data-i18n="missionMultiMissionsInfo"></span>
|
||||||
<span id="multimissionInfo">None</span>
|
<span id="multimissionInfo">None</span>
|
||||||
</div>
|
</div>
|
||||||
<div style="margin-top: 5px">
|
<div style="margin-top: 5px">
|
||||||
<span>Active Mission:</span>
|
<span data-i18n="missionMultiActiveMission"></span>
|
||||||
<span id="activeNissionIndex">1</span>
|
<span id="activeNissionIndex">1</span>
|
||||||
<a class="ic_save disabled" id="setActiveMissionButton" href="#" title="Set Active"></a>
|
<a class="ic_save disabled" id="setActiveMissionButton" href="#" i18n_title="missionTitleSetActive"></a>
|
||||||
</div>
|
</div>
|
||||||
<hr>
|
<hr>
|
||||||
<div style="display: inline-block">
|
<div style="display: inline-block">
|
||||||
<label for="multimissionOptionList">Mission No.</label>
|
<label for="multimissionOptionList" data-i18n="missionMultiMissionNo."></label>
|
||||||
<select name="Number" id="multimissionOptionList" style="width: 50px">
|
<select name="Number" id="multimissionOptionList" style="width: 50px">
|
||||||
<option value="0">ALL</option>
|
<option value="0">ALL</option>
|
||||||
</select>
|
</select>
|
||||||
<div style="float: right">
|
<div style="float: right">
|
||||||
<span>Update All</span>
|
<span data-i18n="missionMultiUpdateAll"></span>
|
||||||
<a class="ic_save disabled" id="updateMultimissionButton" href="#" title="Update All"></a>
|
<a class="ic_save disabled" id="updateMultimissionButton" href="#" i18n_title="missionTitleUpdateAll"></a>
|
||||||
</div>
|
</div>
|
||||||
<div style="margin-bottom: 5px; margin-top: 5px">
|
<div style="margin-bottom: 5px; margin-top: 5px">
|
||||||
<label for="addMultimissionButton">Add New Mission</label>
|
<label for="addMultimissionButton" data-i18n="missionMultiAddNewMission"></label>
|
||||||
<a class="ic_add disabled" id="addMultimissionButton" href="#" title="Add"></a>
|
<a class="ic_add disabled" id="addMultimissionButton" href="#" i18n_title="missionTitleAdd"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -139,12 +139,12 @@
|
||||||
|
|
||||||
<div id="missionPlannerHome" class="gui_box grey" style="display: none">
|
<div id="missionPlannerHome" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionHomeHead">Take Off home</div>
|
<div class="spacer_box_title" data-i18n="missionHomeHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
<div id="showHideHomeButton">
|
<div id="showHideHomeButton">
|
||||||
<a class="ic_hide" href="#" title="Hide"></a>
|
<a class="ic_hide" href="#" i18n_title="missionTitleHide"></a>
|
||||||
</div>
|
</div>
|
||||||
<a id="cancelHome" class="ic_cancel" href="#" title="Cancel"></a>
|
<a id="cancelHome" class="ic_cancel" href="#" i18n_title="missionTitleCancel"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer" id="HomeContent">
|
<div class="spacer" id="HomeContent">
|
||||||
|
@ -160,8 +160,9 @@
|
||||||
</thead>
|
</thead>
|
||||||
<tbody id="homeTableBody">
|
<tbody id="homeTableBody">
|
||||||
<tr>
|
<tr>
|
||||||
<td><div id="viewHomePoint" class="btnTable btnTableIcon">
|
<td>
|
||||||
<a class="ic_center" data-role="home-center" href="#" title="move to center view"></a>
|
<div id="viewHomePoint" class="btnTable btnTableIcon">
|
||||||
|
<a class="ic_center" data-role="home-center" href="#" i18n_title="missionTitleMoveToCenterView"></a>
|
||||||
</div>
|
</div>
|
||||||
</td>
|
</td>
|
||||||
<td><input type="number" class="home-lat" /></td>
|
<td><input type="number" class="home-lat" /></td>
|
||||||
|
@ -173,22 +174,22 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="point" id="elevationEarthModelclass" style="display: none">
|
<div class="point" id="elevationEarthModelclass" style="display: none">
|
||||||
<label class="spacer_box_title i18n-replaced" for="elevationEarthModel">Use Sea Level Earth DEM Model: </label>
|
<label class="spacer_box_title" for="elevationEarthModel" data-i18n="missionLevelEarthDEMModel"></label>
|
||||||
<input id="elevationEarthModel" type="checkbox" value="0" class="togglemedium" checked required>
|
<input id="elevationEarthModel" type="checkbox" value="0" class="togglemedium" checked required>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="missionPlannerSafehome" class="gui_box grey" style="display: none">
|
<div id="missionPlannerSafehome" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionSafehomeHead">Safe Home manager</div>
|
<div class="spacer_box_title" data-i18n="missionSafehomeHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
<div id="showHideSafehomeButton">
|
<div id="showHideSafehomeButton">
|
||||||
<a class="ic_hide" href="#" title="Hide"></a>
|
<a class="ic_hide" href="#" i18n_title="missionTitleHide"></a>
|
||||||
</div>
|
</div>
|
||||||
|
<a id="cancelSafehome" class="ic_cancel" href="#" i18n_title="missionTitleCancel"></a>
|
||||||
|
<a id="saveEepromSafehomeButton" class="ic_save2Eprom" href="#" i18n_title="missionTitleSaveEepromSafehome"></a>
|
||||||
|
<a id="loadEepromSafehomeButton" class="ic_loadFromEprom" href="#" i18n_title="missionTitleLoadEepromSafehome"></a>
|
||||||
<a id="cancelSafehome" class="ic_cancel" href="#" title="Cancel"></a>
|
<a id="cancelSafehome" class="ic_cancel" href="#" title="Cancel"></a>
|
||||||
<a id="saveEepromSafehomeButton" class="ic_save2Eprom" href="#" title="Save Eeprom Safehome"></a>
|
|
||||||
<a id="loadEepromSafehomeButton" class="ic_loadFromEprom" href="#" title="Load Eeprom Safehome"></a>
|
|
||||||
<a id="addSafehome" class="ic_add" href="#" title="Add Safehome"></a>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer" id="SafehomeContent">
|
<div class="spacer" id="SafehomeContent">
|
||||||
|
@ -201,13 +202,19 @@
|
||||||
</div>
|
</div>
|
||||||
<hr>
|
<hr>
|
||||||
<div class="spacer" id="safehomeLegend">
|
<div class="spacer" id="safehomeLegend">
|
||||||
<span><b>Legend : </b></span>
|
<span><b data-i18n="SafehomeLegend"></b></span>
|
||||||
<div class="legendItem">
|
<div class="legendItem">
|
||||||
|
<span class="fill" style="border-bottom-color:#900C3F"></span>
|
||||||
|
<span class="textLegend" data-i18n="SafehomeMaxDistance"></span>
|
||||||
|
<span id="safeHomeMaxDistance" class="valueLegend"></span>
|
||||||
<span class="fill" style="border-bottom:5px dotted #900C3F;"></span>
|
<span class="fill" style="border-bottom:5px dotted #900C3F;"></span>
|
||||||
<span class="textLegend">Max distance (m):</span>
|
<span class="textLegend">Max distance (m):</span>
|
||||||
<span id="safeHomeMaxDistance"></span>
|
<span id="safeHomeMaxDistance"></span>
|
||||||
</div>
|
</div>
|
||||||
<div class="legendItem">
|
<div class="legendItem">
|
||||||
|
<span class="fill"></span>
|
||||||
|
<span class="textLegend" data-i18n="SafehomeSafeRadius"></span>
|
||||||
|
<span id="SafeHomeSafeDistance" class="valueLegend"></span>
|
||||||
<span class="fill" style="border-bottom:5px dotted #88CC3E;"></span>
|
<span class="fill" style="border-bottom:5px dotted #88CC3E;"></span>
|
||||||
<span class="textLegend">Safe Radius (m):</span>
|
<span class="textLegend">Safe Radius (m):</span>
|
||||||
<span id="SafeHomeSafeDistance"></span>
|
<span id="SafeHomeSafeDistance"></span>
|
||||||
|
@ -224,16 +231,16 @@
|
||||||
|
|
||||||
<div class="gui_box grey" id="MPeditPoint" style="display: none">
|
<div class="gui_box grey" id="MPeditPoint" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="editPointHead" id="EditPointNumber">Edit point</div>
|
<div class="spacer_box_title" data-i18n="editPointHead" id="EditPointNumber"></div>
|
||||||
<div class="btnMenu btnMenuIcon">
|
<div class="btnMenu btnMenuIcon">
|
||||||
<div id="showHideWPeditButton" class="save_btn">
|
<div id="showHideWPeditButton" class="save_btn">
|
||||||
<a class="ic_hide" href="#" title="Hide"></a>
|
<a class="ic_hide" href="#" i18n_title="missionTitleHide"></a>
|
||||||
</div>
|
</div>
|
||||||
<div id="removePoint" class="btn btnMenu-danger">
|
<div id="removePoint" class="btn btnMenu-danger">
|
||||||
<a id="removePointButton" class="ic_removeAll" href="#" title="Remove"></a>
|
<a id="removePointButton" class="ic_removeAll" href="#" i18n_title="missionTitlRemove"></a>
|
||||||
</div>
|
</div>
|
||||||
<div id="editMission" class="save_btn" style="display: none">
|
<div id="editMission" class="save_btn" style="display: none">
|
||||||
<a id="editMissionButton" class="ic_setup" href="#" title="Edit Mission"></a>
|
<a id="editMissionButton" class="ic_setup" href="#" i18n_title="missionTitlEditMission"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -281,7 +288,7 @@
|
||||||
<label class="point-label" for="pointP1">Parameter 1: </label>
|
<label class="point-label" for="pointP1">Parameter 1: </label>
|
||||||
<input id="pointP1" type="text" value="0" required>
|
<input id="pointP1" type="text" value="0" required>
|
||||||
</div>
|
</div>
|
||||||
<div class="point" id="pointP2class" style="display: none">
|
<div class="point" id="pointP2class" style="display: none">
|
||||||
<label class="point-label" for="pointP2">Parameter 2: </label>
|
<label class="point-label" for="pointP2">Parameter 2: </label>
|
||||||
<input id="pointP2" type="text" value="0" required>
|
<input id="pointP2" type="text" value="0" required>
|
||||||
</div>
|
</div>
|
||||||
|
@ -293,6 +300,23 @@
|
||||||
<div class="userActionContainer">4 <input id="pointP3UserAction4" type="checkbox" value="0" class="togglemedium" checked required></div>
|
<div class="userActionContainer">4 <input id="pointP3UserAction4" type="checkbox" value="0" class="togglemedium" checked required></div>
|
||||||
</div>
|
</div>
|
||||||
<div>
|
<div>
|
||||||
|
<table class="waypointOptionsTable">
|
||||||
|
<thead>
|
||||||
|
<tr>
|
||||||
|
<th style="width: 30px">
|
||||||
|
<div id="addOptionsPoint" class="btn btnTable btnTableIcon btnTable-success">
|
||||||
|
<a id="addOptionsPointButton" class="ic_add" data-role="waypointOptions-add" href="#" style="float: center" title="Add"></a>
|
||||||
|
</div>
|
||||||
|
</th>
|
||||||
|
<th style="width: 50px" data-i18n="WaypointOptionId"></th>
|
||||||
|
<th style="width: 80px" data-i18n="WaypointOptionAction"></th>
|
||||||
|
<th style="width: 120px" data-i18n="WaypointOptionP1"></th>
|
||||||
|
<th style="width: 120px" data-i18n="WaypointOptionP2"></th>
|
||||||
|
</tr>
|
||||||
|
</thead>
|
||||||
|
<tbody id="waypointOptionsTableBody">
|
||||||
|
</tbody>
|
||||||
|
</table>
|
||||||
<table class="waypointOptionsTable">
|
<table class="waypointOptionsTable">
|
||||||
<thead>
|
<thead>
|
||||||
<tr>
|
<tr>
|
||||||
|
@ -344,7 +368,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<!-- <div class="point-radio" id="pointOptionclass" style="display: none">
|
<!-- <div class="point-radio" id="pointOptionclass" style="display: none">
|
||||||
<div class="radio-line">
|
<div class="radio-line">
|
||||||
<input type="radio" id="Options_None" name="Options" value="None" checked>
|
<input type="radio" id="Options_None" name="Options" value="None" checked>
|
||||||
<label class="radio-options" for="Options_None">None</label><br>
|
<label class="radio-options" for="Options_None">None</label><br>
|
||||||
|
@ -378,17 +402,17 @@
|
||||||
<div class="cf_column threefourth_left" style="height: 100%;">
|
<div class="cf_column threefourth_left" style="height: 100%;">
|
||||||
<div id="missionMap"></div>
|
<div id="missionMap"></div>
|
||||||
<div id="missionPlannerElevation" class="gui_box grey" style="display: none">
|
<div id="missionPlannerElevation" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionDefaultElevationHead">Elevation Profile</div>
|
<div class="spacer_box_title" data-i18n="missionDefaultElevationHead"></div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
<a id="cancelPlot" class="ic_cancel" href="#" title="Cancel"></a>
|
<a id="cancelPlot" class="ic_cancel" href="#" i18n_title="missionTitleCancel"></a>
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer">
|
|
||||||
<div id="elevationDiv">
|
|
||||||
</div>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="spacer">
|
||||||
|
<div id="elevationDiv">
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
<div id="notLoadMap" data-i18n="useOnlyStandalone" style="display: none;"></div>
|
<div id="notLoadMap" data-i18n="useOnlyStandalone" style="display: none;"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -2217,7 +2217,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
clearEditForm();
|
clearEditForm();
|
||||||
} catch (e) {
|
} catch (e) {
|
||||||
console.log(e);
|
console.log(e);
|
||||||
GUI.log("Previous selection was not a WAYPOINT!");
|
GUI.log(chrome.i18n.getMessage('notAWAYPOINT'));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
selectedFeature = map.forEachFeatureAtPixel(evt.pixel,
|
selectedFeature = map.forEachFeatureAtPixel(evt.pixel,
|
||||||
|
@ -2886,15 +2886,15 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
cleanSafehomeLayers();
|
cleanSafehomeLayers();
|
||||||
renderSafehomesOnMap();
|
renderSafehomesOnMap();
|
||||||
updateSafehomeInfo();
|
updateSafehomeInfo();
|
||||||
GUI.log('End of getting Safehome points');
|
GUI.log(chrome.i18n.getMessage('endGettingSafehomePoints'));
|
||||||
$('#loadEepromSafehomeButton').removeClass('disabled');
|
$('#loadEepromSafehomeButton').removeClass('disabled');
|
||||||
}, 500);
|
}, 500);
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
$('#saveEepromSafehomeButton').on('click', function () {
|
$('#saveEepromSafehomeButton').on('click', function() {
|
||||||
$(this).addClass('disabled');
|
$(this).addClass('disabled');
|
||||||
GUI.log('Start of sending Safehome points');
|
GUI.log(chrome.i18n.getMessage('startSendingSafehomePoints'));
|
||||||
|
|
||||||
var saveChainer = new MSPChainerClass();
|
var saveChainer = new MSPChainerClass();
|
||||||
saveChainer.setChain([
|
saveChainer.setChain([
|
||||||
|
@ -2902,7 +2902,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
mspHelper.saveFwApproach,
|
mspHelper.saveFwApproach,
|
||||||
function() {
|
function() {
|
||||||
mspHelper.saveToEeprom();
|
mspHelper.saveToEeprom();
|
||||||
GUI.log('End of sending Safehome points');
|
GUI.log(chrome.i18n.getMessage('endSendingSafehomePoints'));
|
||||||
$('#saveEepromSafehomeButton').removeClass('disabled');
|
$('#saveEepromSafehomeButton').removeClass('disabled');
|
||||||
}
|
}
|
||||||
]);
|
]);
|
||||||
|
@ -3068,7 +3068,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
if ((markers.length || multimissionCount) && !confirm(chrome.i18n.getMessage(message))) return;
|
if ((markers.length || multimissionCount) && !confirm(chrome.i18n.getMessage(message))) return;
|
||||||
removeAllWaypoints();
|
removeAllWaypoints();
|
||||||
$(this).addClass('disabled');
|
$(this).addClass('disabled');
|
||||||
GUI.log('Start get point');
|
GUI.log(chrome.i18n.getMessage('startGetPoint'));
|
||||||
getWaypointsFromFC(false);
|
getWaypointsFromFC(false);
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -3078,7 +3078,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
$(this).addClass('disabled');
|
$(this).addClass('disabled');
|
||||||
GUI.log('Start send point');
|
GUI.log(chrome.i18n.getMessage('startSendPoint'));
|
||||||
sendWaypointsToFC(false);
|
sendWaypointsToFC(false);
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -3087,7 +3087,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
if ((markers.length || multimissionCount) && !confirm(chrome.i18n.getMessage(message))) return;
|
if ((markers.length || multimissionCount) && !confirm(chrome.i18n.getMessage(message))) return;
|
||||||
removeAllWaypoints();
|
removeAllWaypoints();
|
||||||
$(this).addClass('disabled');
|
$(this).addClass('disabled');
|
||||||
GUI.log('Start get point');
|
GUI.log(chrome.i18n.getMessage('startGetPoint'));
|
||||||
getWaypointsFromFC(true);
|
getWaypointsFromFC(true);
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -3097,7 +3097,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
$(this).addClass('disabled');
|
$(this).addClass('disabled');
|
||||||
GUI.log('Start send point');
|
GUI.log(chrome.i18n.getMessage('startSendPoint'));
|
||||||
sendWaypointsToFC(true);
|
sendWaypointsToFC(true);
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -3131,7 +3131,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
function loadMissionFile(filename) {
|
function loadMissionFile(filename) {
|
||||||
const fs = require('fs');
|
const fs = require('fs');
|
||||||
if (!window.xml2js) return GUI.log('<span style="color: red">Error reading file (xml2js not found)</span>');
|
if (!window.xml2js) return GUI.log(chrome.i18n.getMessage('errorReadingFileXml2jsNotFound'));
|
||||||
|
|
||||||
for (let i = SAFEHOMES.getMaxSafehomeCount(); i < FW_APPROACH.getMaxFwApproachCount(); i++) {
|
for (let i = SAFEHOMES.getMaxSafehomeCount(); i < FW_APPROACH.getMaxFwApproachCount(); i++) {
|
||||||
FW_APPROACH.clean(i);
|
FW_APPROACH.clean(i);
|
||||||
|
@ -3139,13 +3139,13 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
|
|
||||||
fs.readFile(filename, (err, data) => {
|
fs.readFile(filename, (err, data) => {
|
||||||
if (err) {
|
if (err) {
|
||||||
GUI.log('<span style="color: red">Error reading file</span>');
|
GUI.log(chrome.i18n.getMessage('errorReadingFile'));
|
||||||
return console.error(err);
|
return console.error(err);
|
||||||
}
|
}
|
||||||
|
|
||||||
window.xml2js.Parser({ 'explicitChildren': true, 'preserveChildrenOrder': true }).parseString(data, (err, result) => {
|
window.xml2js.Parser({ 'explicitChildren': true, 'preserveChildrenOrder': true }).parseString(data, (err, result) => {
|
||||||
if (err) {
|
if (err) {
|
||||||
GUI.log('<span style="color: red">Error parsing file</span>');
|
GUI.log(chrome.i18n.getMessage('errorParsingFile'));
|
||||||
return console.error(err);
|
return console.error(err);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3306,7 +3306,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
updateTotalInfo();
|
updateTotalInfo();
|
||||||
let sFilename = String(filename.split('\\').pop().split('/').pop());
|
let sFilename = String(filename.split('\\').pop().split('/').pop());
|
||||||
GUI.log(sFilename+' has been loaded successfully !');
|
GUI.log(sFilename + chrome.i18n.getMessage('loadedSuccessfully'));
|
||||||
updateFilename(sFilename);
|
updateFilename(sFilename);
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
@ -3314,7 +3314,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
|
|
||||||
function saveMissionFile(filename) {
|
function saveMissionFile(filename) {
|
||||||
const fs = require('fs');
|
const fs = require('fs');
|
||||||
if (!window.xml2js) return GUI.log('<span style="color: red">Error writing file (xml2js not found)</span>');
|
if (!window.xml2js) return GUI.log(chrome.i18n.getMessage('errorWritingFileXml2jsNotFound'));
|
||||||
|
|
||||||
var center = ol.proj.toLonLat(map.getView().getCenter());
|
var center = ol.proj.toLonLat(map.getView().getCenter());
|
||||||
var zoom = map.getView().getZoom();
|
var zoom = map.getView().getZoom();
|
||||||
|
@ -3382,11 +3382,11 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
xml = xml.replace(/missionitem mission/g, 'meta mission');
|
xml = xml.replace(/missionitem mission/g, 'meta mission');
|
||||||
fs.writeFile(filename, xml, (err) => {
|
fs.writeFile(filename, xml, (err) => {
|
||||||
if (err) {
|
if (err) {
|
||||||
GUI.log('<span style="color: red">Error writing file</span>');
|
GUI.log(chrome.i18n.getMessage('ErrorWritingFile'));
|
||||||
return console.error(err);
|
return console.error(err);
|
||||||
}
|
}
|
||||||
let sFilename = String(filename.split('\\').pop().split('/').pop());
|
let sFilename = String(filename.split('\\').pop().split('/').pop());
|
||||||
GUI.log(sFilename+' has been saved successfully !');
|
GUI.log(sFilename + chrome.i18n.getMessage('savedSuccessfully'));
|
||||||
updateFilename(sFilename);
|
updateFilename(sFilename);
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
@ -3410,7 +3410,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
function getWaypointData() {
|
function getWaypointData() {
|
||||||
|
|
||||||
mspHelper.loadWaypoints(function() {
|
mspHelper.loadWaypoints(function() {
|
||||||
GUI.log('End get point');
|
GUI.log(chrome.i18n.getMessage('endGetPoint'));
|
||||||
if (loadEeprom) {
|
if (loadEeprom) {
|
||||||
GUI.log(chrome.i18n.getMessage('eeprom_load_ok'));
|
GUI.log(chrome.i18n.getMessage('eeprom_load_ok'));
|
||||||
$('#loadEepromMissionButton').removeClass('disabled');
|
$('#loadEepromMissionButton').removeClass('disabled');
|
||||||
|
@ -3458,7 +3458,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
mspHelper.saveWaypoints,
|
mspHelper.saveWaypoints,
|
||||||
mspHelper.saveFwApproach,
|
mspHelper.saveFwApproach,
|
||||||
function () {
|
function () {
|
||||||
GUI.log('End send point');
|
GUI.log(chrome.i18n.getMessage('endSendPoint'));
|
||||||
if (saveEeprom) {
|
if (saveEeprom) {
|
||||||
$('#saveEepromMissionButton').removeClass('disabled');
|
$('#saveEepromMissionButton').removeClass('disabled');
|
||||||
GUI.log(chrome.i18n.getMessage('eeprom_saved_ok'));
|
GUI.log(chrome.i18n.getMessage('eeprom_saved_ok'));
|
||||||
|
|
|
@ -20,14 +20,21 @@
|
||||||
<label for="motor_direction_inverted"><span data-i18n="motor_direction_inverted"></span></label>
|
<label for="motor_direction_inverted"><span data-i18n="motor_direction_inverted"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="motor_direction_inverted_hint"></div>
|
<div class="helpicon cf_tip" data-i18n_title="motor_direction_inverted_hint"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="select">
|
<div class="checkbox">
|
||||||
<select id="output_mode" data-setting="output_mode"></select>
|
<input id="mixer_pid_profile_linking" type="checkbox" class="toggle" data-setting="mixer_pid_profile_linking" />
|
||||||
<label for="output_mode">
|
<label for="mixer_pid_profile_linking"><span data-i18n="mixer_pid_profile_linking"></span></label>
|
||||||
<span data-i18n="output_modeTitle"></span>
|
<div class="helpicon cf_tip" data-i18n_title="mixer_pid_profile_linking_hint"></div>
|
||||||
</label>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<div class="platform-type gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="timerOutputs"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box" id="timerOutputsList" style="padding: 0; width: calc(100% - 12px)"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
<div class="platform-type gui_box grey">
|
<div class="platform-type gui_box grey">
|
||||||
|
@ -42,7 +49,7 @@
|
||||||
<div class="half" style="width: calc(50% - 10px); margin-left: 10px;">
|
<div class="half" style="width: calc(50% - 10px); margin-left: 10px;">
|
||||||
<select id="mixer-preset"></select>
|
<select id="mixer-preset"></select>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="mixer-load-button">
|
<div class="mixer-load-button">
|
||||||
<div id="needToUpdateMixerMessage" class="is-hidden" data-i18n="mixerNotLoaded"></div>
|
<div id="needToUpdateMixerMessage" class="is-hidden" data-i18n="mixerNotLoaded"></div>
|
||||||
<div class="btn default_btn narrow green is-hidden">
|
<div class="btn default_btn narrow green is-hidden">
|
||||||
|
@ -90,7 +97,7 @@
|
||||||
<table id="motor-mix-table" class="mixer-table">
|
<table id="motor-mix-table" class="mixer-table">
|
||||||
<thead>
|
<thead>
|
||||||
<tr>
|
<tr>
|
||||||
<th style="width: 75px">Motor</th>
|
<th style="width: 75px" data-i18n="controlAxisMotor"></th>
|
||||||
<th data-i18n="controlAxisThrottle"></th>
|
<th data-i18n="controlAxisThrottle"></th>
|
||||||
<th data-i18n="controlAxisRoll"></th>
|
<th data-i18n="controlAxisRoll"></th>
|
||||||
<th data-i18n="controlAxisPitch"></th>
|
<th data-i18n="controlAxisPitch"></th>
|
||||||
|
|
|
@ -27,7 +27,8 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
mspHelper.loadMotors,
|
mspHelper.loadMotors,
|
||||||
mspHelper.loadServoMixRules,
|
mspHelper.loadServoMixRules,
|
||||||
mspHelper.loadMotorMixRules,
|
mspHelper.loadMotorMixRules,
|
||||||
mspHelper.loadOutputMapping,
|
mspHelper.loadOutputMappingExt,
|
||||||
|
mspHelper.loadTimerOutputModes,
|
||||||
mspHelper.loadLogicConditions
|
mspHelper.loadLogicConditions
|
||||||
]);
|
]);
|
||||||
loadChainer.setExitPoint(loadHtml);
|
loadChainer.setExitPoint(loadHtml);
|
||||||
|
@ -37,6 +38,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
mspHelper.saveMixerConfig,
|
mspHelper.saveMixerConfig,
|
||||||
mspHelper.sendServoMixer,
|
mspHelper.sendServoMixer,
|
||||||
mspHelper.sendMotorMixer,
|
mspHelper.sendMotorMixer,
|
||||||
|
mspHelper.sendTimerOutputModes,
|
||||||
saveSettings,
|
saveSettings,
|
||||||
mspHelper.saveToEeprom
|
mspHelper.saveToEeprom
|
||||||
]);
|
]);
|
||||||
|
@ -72,9 +74,13 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
$outputRow.append('<th data-i18n="mappingTableOutput"></th>');
|
$outputRow.append('<th data-i18n="mappingTableOutput"></th>');
|
||||||
$functionRow.append('<th data-i18n="mappingTableFunction"></th>');
|
$functionRow.append('<th data-i18n="mappingTableFunction"></th>');
|
||||||
|
|
||||||
for (let i = 1; i <= outputCount; i++) {
|
for (let i = 1; i <= outputCount; i++) {
|
||||||
$outputRow.append('<td>S' + i + '</td>');
|
|
||||||
|
let timerId = OUTPUT_MAPPING.getTimerId(i - 1);
|
||||||
|
let color = OUTPUT_MAPPING.getOutputTimerColor(i - 1);
|
||||||
|
|
||||||
|
$outputRow.append('<td style="background-color: ' + color + '">S' + i + ' (Timer ' + (timerId + 1) + ')</td>');
|
||||||
$functionRow.append('<td id="function-' + i +'">-</td>');
|
$functionRow.append('<td id="function-' + i +'">-</td>');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -82,6 +88,44 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function updateTimerOverride() {
|
||||||
|
let timers = OUTPUT_MAPPING.getUsedTimerIds();
|
||||||
|
|
||||||
|
for(let i =0; i < timers.length;++i) {
|
||||||
|
let timerId = timers[i];
|
||||||
|
$select = $('#timer-output-' + timerId);
|
||||||
|
if(!$select) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
OUTPUT_MAPPING.setTimerOverride(timerId, $select.val());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function renderTimerOverride() {
|
||||||
|
let outputCount = OUTPUT_MAPPING.getOutputCount(),
|
||||||
|
$container = $('#timerOutputsList'), timers = {};
|
||||||
|
|
||||||
|
|
||||||
|
let usedTimers = OUTPUT_MAPPING.getUsedTimerIds();
|
||||||
|
|
||||||
|
for (t of usedTimers) {
|
||||||
|
var usageMode = OUTPUT_MAPPING.getTimerOverride(t);
|
||||||
|
$container.append(
|
||||||
|
'<div class="select" style="padding: 5px; margin: 1px; background-color: ' + OUTPUT_MAPPING.getTimerColor(t) + '">' +
|
||||||
|
'<select id="timer-output-' + t + '">' +
|
||||||
|
'<option value=' + OUTPUT_MAPPING.TIMER_OUTPUT_MODE_AUTO + '' + (usageMode == OUTPUT_MAPPING.TIMER_OUTPUT_MODE_AUTO ? ' selected' : '')+ '>AUTO</option>'+
|
||||||
|
'<option value=' + OUTPUT_MAPPING.TIMER_OUTPUT_MODE_MOTORS + '' + (usageMode == OUTPUT_MAPPING.TIMER_OUTPUT_MODE_MOTORS ? ' selected' : '')+ '>MOTORS</option>'+
|
||||||
|
'<option value=' + OUTPUT_MAPPING.TIMER_OUTPUT_MODE_SERVOS + '' + (usageMode == OUTPUT_MAPPING.TIMER_OUTPUT_MODE_SERVOS ? ' selected' : '')+ '>SERVOS</option>'+
|
||||||
|
'</select>' +
|
||||||
|
'<label for="timer-output-' + t + '">' +
|
||||||
|
'<span> Timer ' + (parseInt(t) + 1) + '</span>' +
|
||||||
|
'</label>' +
|
||||||
|
'</div>'
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
function renderOutputMapping() {
|
function renderOutputMapping() {
|
||||||
let outputMap = OUTPUT_MAPPING.getOutputTable(
|
let outputMap = OUTPUT_MAPPING.getOutputTable(
|
||||||
MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER,
|
MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER,
|
||||||
|
@ -126,8 +170,9 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
motors.push(outputPad);
|
motors.push(outputPad);
|
||||||
} else {
|
} else {
|
||||||
let servo = servoRules.getServoMixRuleFromTarget(omIndex[1]);
|
let servo = servoRules.getServoMixRuleFromTarget(omIndex[1]);
|
||||||
|
if (servo == null) {continue;}
|
||||||
let divID = "servoPreview" + omIndex[1];
|
let divID = "servoPreview" + omIndex[1];
|
||||||
|
|
||||||
switch (parseInt(servo.getInput())) {
|
switch (parseInt(servo.getInput())) {
|
||||||
case INPUT_STABILIZED_PITCH:
|
case INPUT_STABILIZED_PITCH:
|
||||||
case STABILIZED_PITCH_POSITIVE:
|
case STABILIZED_PITCH_POSITIVE:
|
||||||
|
@ -352,7 +397,6 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
const $fixedValueCalcInput = row.find(".mix-rule-fixed-value");
|
const $fixedValueCalcInput = row.find(".mix-rule-fixed-value");
|
||||||
if (FC.getServoMixInputNames()[$mixRuleInput.val()] === 'MAX') {
|
if (FC.getServoMixInputNames()[$mixRuleInput.val()] === 'MAX') {
|
||||||
$fixedValueCalcInput.show();
|
$fixedValueCalcInput.show();
|
||||||
row.find(".mix-rule-speed").prop('disabled', true);
|
|
||||||
} else {
|
} else {
|
||||||
$fixedValueCalcInput.hide();
|
$fixedValueCalcInput.hide();
|
||||||
row.find(".mix-rule-speed").prop('disabled', false);
|
row.find(".mix-rule-speed").prop('disabled', false);
|
||||||
|
@ -392,7 +436,10 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
$motorMixTableBody.append('\
|
$motorMixTableBody.append('\
|
||||||
<tr>\
|
<tr>\
|
||||||
<td><span class="mix-rule-motor"></span></td>\
|
<td><span class="mix-rule-motor"></span></td>\
|
||||||
<td><input type="number" class="mix-rule-throttle" step="0.001" min="0" max="1" /></td>\
|
<td>\
|
||||||
|
<input type="number" class="mix-rule-throttle" step="0.001" min="-2" max="2" />\
|
||||||
|
<div class="throttle-warning-text" data-i18n="mixerThrottleWarning" ></div>\
|
||||||
|
</td>\
|
||||||
<td><input type="number" class="mix-rule-roll" step="0.001" min="-2" max="2" /></td>\
|
<td><input type="number" class="mix-rule-roll" step="0.001" min="-2" max="2" /></td>\
|
||||||
<td><input type="number" class="mix-rule-pitch" step="0.001" min="-2" max="2" /></td>\
|
<td><input type="number" class="mix-rule-pitch" step="0.001" min="-2" max="2" /></td>\
|
||||||
<td><input type="number" class="mix-rule-yaw" step="0.001" min="-2" max="2" /></td>\
|
<td><input type="number" class="mix-rule-yaw" step="0.001" min="-2" max="2" /></td>\
|
||||||
|
@ -403,9 +450,26 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
const $row = $motorMixTableBody.find('tr:last');
|
const $row = $motorMixTableBody.find('tr:last');
|
||||||
|
|
||||||
$row.find('.mix-rule-motor').html(index);
|
$row.find('.mix-rule-motor').html(index);
|
||||||
$row.find('.mix-rule-throttle').val(rule.getThrottle()).change(function () {
|
const $throttleInput = $row.find('.mix-rule-throttle').val(rule.getThrottle());
|
||||||
rule.setThrottle($(this).val());
|
const $warningBox = $row.find('.throttle-warning-text');
|
||||||
});
|
|
||||||
|
// Function to update throttle and show/hide warning box
|
||||||
|
function updateThrottle() {
|
||||||
|
rule.setThrottle($throttleInput.val());
|
||||||
|
// Change color if value exceeds 1
|
||||||
|
if (parseFloat($throttleInput.val()) > 1 || parseFloat($throttleInput.val()) < 0) {
|
||||||
|
$throttleInput.css('background-color', 'orange');
|
||||||
|
// Show warning box
|
||||||
|
$warningBox.show();
|
||||||
|
} else {
|
||||||
|
$throttleInput.css('background-color', ''); // Reset to default
|
||||||
|
// Hide warning box
|
||||||
|
$warningBox.hide();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
updateThrottle();
|
||||||
|
$throttleInput.change(updateThrottle);
|
||||||
|
|
||||||
$row.find('.mix-rule-roll').val(rule.getRoll()).change(function () {
|
$row.find('.mix-rule-roll').val(rule.getRoll()).change(function () {
|
||||||
rule.setRoll($(this).val());
|
rule.setRoll($(this).val());
|
||||||
});
|
});
|
||||||
|
@ -437,6 +501,9 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
SERVO_RULES.inflate();
|
SERVO_RULES.inflate();
|
||||||
MOTOR_RULES.cleanup();
|
MOTOR_RULES.cleanup();
|
||||||
MOTOR_RULES.inflate();
|
MOTOR_RULES.inflate();
|
||||||
|
|
||||||
|
updateTimerOverride();
|
||||||
|
|
||||||
saveChainer.execute();
|
saveChainer.execute();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -601,6 +668,11 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
$('#platform-type').parent('.select').addClass('no-bottom-border');
|
$('#platform-type').parent('.select').addClass('no-bottom-border');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!updateEzTuneTabVisibility(false)) {
|
||||||
|
EZ_TUNE.enabled = 0;
|
||||||
|
mspHelper.saveEzTune();
|
||||||
|
}
|
||||||
|
|
||||||
updateRefreshButtonStatus();
|
updateRefreshButtonStatus();
|
||||||
|
|
||||||
updateMotorDirection();
|
updateMotorDirection();
|
||||||
|
@ -704,6 +776,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
renderOutputTable();
|
renderOutputTable();
|
||||||
renderOutputMapping();
|
renderOutputMapping();
|
||||||
|
renderTimerOverride();
|
||||||
|
|
||||||
LOGIC_CONDITIONS.init($('#logic-wrapper'));
|
LOGIC_CONDITIONS.init($('#logic-wrapper'));
|
||||||
|
|
||||||
|
|
|
@ -3,7 +3,7 @@
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="tab_title" data-i18n="tabOnboardLogging"></div>
|
<div class="tab_title" data-i18n="tabOnboardLogging"></div>
|
||||||
<div class="require-blackbox-unsupported">
|
<div class="require-blackbox-unsupported">
|
||||||
|
|
||||||
<div class="gui_box grey require-blackbox-config-supported">
|
<div class="gui_box grey require-blackbox-config-supported">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" data-i18n="blackboxConfiguration"></div>
|
<div class="spacer_box_title" data-i18n="blackboxConfiguration"></div>
|
||||||
|
@ -31,22 +31,22 @@
|
||||||
<div class="spacer_box_title" data-i18n="blackboxConfiguration"></div>
|
<div class="spacer_box_title" data-i18n="blackboxConfiguration"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="checkbox">
|
<div class="checkbox">
|
||||||
<input checked type="checkbox" data-bit="19" class="feature toggle" name="BLACKBOX" title="BLACKBOX" id="feature-19-2">
|
<input checked type="checkbox" data-bit="19" class="feature toggle" name="BLACKBOX" title="BLACKBOX" id="feature-19-2">
|
||||||
<label for="feature-19-2">
|
<label for="feature-19-2">
|
||||||
<span data-i18n="featureBLACKBOX"></span>
|
<span data-i18n="featureBLACKBOX"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div class="select line blackboxDevice">
|
<div class="select line blackboxDevice">
|
||||||
<select name="blackbox_device">
|
<select name="blackbox_device">
|
||||||
</select>
|
</select>
|
||||||
<span>Blackbox logging device</span>
|
<span i18n="onboardLoggingBlackbox"></span>
|
||||||
</div>
|
</div>
|
||||||
<div class="select line blackboxRate">
|
<div class="select line blackboxRate">
|
||||||
<select name="blackbox_rate">
|
<select name="blackbox_rate">
|
||||||
</select>
|
</select>
|
||||||
<span>Portion of flight loop iterations to log (logging rate)</span>
|
<span i18n="onboardLoggingBlackboxRate"></span>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -56,45 +56,43 @@
|
||||||
<div class="spacer_box_title" data-i18n="blackboxFields"></div>
|
<div class="spacer_box_title" data-i18n="blackboxFields"></div>
|
||||||
</div>
|
</div>
|
||||||
<div id="blackBoxFlagsDiv" class="spacer_box config-section">
|
<div id="blackBoxFlagsDiv" class="spacer_box config-section">
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar" align="left">
|
<div class="gui_box_titlebar" align="left">
|
||||||
<div class="spacer_box_title">
|
<div class="spacer_box_title" data-i18n="serialLogging">
|
||||||
Outboard serial logging device
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<p data-i18n="serialLoggingSupportedNote"></p>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
|
||||||
<p data-i18n="serialLoggingSupportedNote"></p>
|
<div class="gui_box grey require-dataflash-supported">
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="gui_box grey require-dataflash-supported">
|
|
||||||
<div class="gui_box_titlebar" align="left">
|
<div class="gui_box_titlebar" align="left">
|
||||||
<div class="spacer_box_title">
|
<div class="spacer_box_title" data-i18n="onboardLoggingFlashLogger">
|
||||||
Onboard dataflash chip
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="require-dataflash-supported">
|
<div class="require-dataflash-supported">
|
||||||
<p data-i18n="dataflashNote"></p>
|
<p data-i18n="dataflashNote"></p>
|
||||||
|
|
||||||
<dialog class="dataflash-confirm-erase">
|
<dialog class="dataflash-confirm-erase">
|
||||||
<h3 data-i18n="dataflashConfirmEraseTitle"></h3>
|
<h3 data-i18n="dataflashConfirmEraseTitle"></h3>
|
||||||
<div class="dataflash-confirm-erase-note" data-i18n="dataflashConfirmEraseNote"></div>
|
<div class="dataflash-confirm-erase-note" data-i18n="dataflashConfirmEraseNote"></div>
|
||||||
<div class="dataflash-erase-progress">
|
<div class="dataflash-erase-progress">
|
||||||
<div class="data-loading">
|
<div class="data-loading">
|
||||||
<p>Erase in progress, please wait...</p>
|
<p data-i18n="dataflashEraseing"></p>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="buttons">
|
<div class="buttons">
|
||||||
<a href="#" class="erase-flash-confirm regular-button" data-i18n="dataflashButtonEraseConfirm"></a>
|
<a href="#" class="erase-flash-confirm regular-button" data-i18n="dataflashButtonEraseConfirm"></a>
|
||||||
<a href="#" class="erase-flash-cancel regular-button" data-i18n="dataflashButtonEraseCancel"></a>
|
<a href="#" class="erase-flash-cancel regular-button" data-i18n="dataflashButtonEraseCancel"></a>
|
||||||
</div>
|
</div>
|
||||||
</dialog>
|
</dialog>
|
||||||
|
|
||||||
<dialog class="dataflash-saving">
|
<dialog class="dataflash-saving">
|
||||||
<h3 data-i18n="dataflashSavingTitle"></h3>
|
<h3 data-i18n="dataflashSavingTitle"></h3>
|
||||||
<div class="dataflash-saving-before">
|
<div class="dataflash-saving-before">
|
||||||
|
@ -111,7 +109,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</dialog>
|
</dialog>
|
||||||
|
|
||||||
<ul class="dataflash-contents">
|
<ul class="dataflash-contents">
|
||||||
<li class="dataflash-used">
|
<li class="dataflash-used">
|
||||||
<div class="legend"></div>
|
<div class="legend"></div>
|
||||||
|
@ -120,32 +118,31 @@
|
||||||
<div class="legend"></div>
|
<div class="legend"></div>
|
||||||
</li>
|
</li>
|
||||||
</ul>
|
</ul>
|
||||||
|
|
||||||
<div>
|
<div>
|
||||||
<a class="regular-button erase-flash" href="#" data-i18n="dataflashButtonErase"></a>
|
<a class="regular-button erase-flash" href="#" data-i18n="dataflashButtonErase"></a>
|
||||||
<a class="regular-button save-flash" href="#" data-i18n="dataflashButtonSaveFile"></a>
|
<a class="regular-button save-flash" href="#" data-i18n="dataflashButtonSaveFile"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<p class="require-dataflash-not-present" data-i18n="dataflashNotPresentNote"></p>
|
<p class="require-dataflash-not-present" data-i18n="dataflashNotPresentNote"></p>
|
||||||
<p class="require-dataflash-unsupported" data-i18n="dataflashFirmwareUpgradeRequired"></p>
|
<p class="require-dataflash-unsupported" data-i18n="dataflashFirmwareUpgradeRequired"></p>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="require-sdcard-supported">
|
<div class="require-sdcard-supported">
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar" align="left">
|
<div class="gui_box_titlebar" align="left">
|
||||||
<div class="spacer_box_title">
|
<div class="spacer_box_title" data-i18n="OnboardSDCard">
|
||||||
Onboard SD card
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
<div class="spacer_box">
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="sdcard">
|
<div class="sdcard">
|
||||||
<div class="sdcard-icon"></div>
|
<div class="sdcard-icon"></div>
|
||||||
<div class="sdcard-status"></div>
|
<div class="sdcard-status"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<p data-i18n="sdcardNote"></p>
|
<p data-i18n="sdcardNote"></p>
|
||||||
|
|
||||||
<div class="require-sdcard-ready">
|
<div class="require-sdcard-ready">
|
||||||
<ul class="sdcard-contents">
|
<ul class="sdcard-contents">
|
||||||
<li class="sdcard-other">
|
<li class="sdcard-other">
|
||||||
|
@ -166,4 +163,4 @@
|
||||||
<a href="#" class="save-settings regular-button" data-i18n="blackboxButtonSave"></a>
|
<a href="#" class="save-settings regular-button" data-i18n="blackboxButtonSave"></a>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|