1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-13 19:40:22 +03:00

Merge remote-tracking branch 'iNavFlight/master' into magnetometer_tab_improvments

# Conflicts:
#	_locales/en/messages.json
This commit is contained in:
Luca 2022-03-26 15:50:02 +01:00
commit ce0b4dac66
72 changed files with 2879 additions and 2488 deletions

View file

@ -6,6 +6,18 @@ It runs as an app within Google Chrome and allows you to configure the INAV soft
Various types of aircraft are supported by the tool and by INAV, e.g. quadcopters, hexacopters, octocopters and fixed-wing aircraft.
# 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).
GitHub issue tracker is reserved for bugs and other technical problems. If you do not know how to setup
everything, hardware is not working or have any other _support_ problem, please consult:
* [INAV Discord Server](https://discord.gg/peg2hhbYwN)
* [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)
* [INAV Official on Telegram](https://t.me/INAVFlight)
## INAV Configurator start minimized, what should I do?
You have to remove `C:\Users%Your_UserNname%\AppData\Local\inav-configurator` folder and all its content.
@ -42,11 +54,7 @@ Depending on target operating system, _INAV Configurator_ is distributed as _sta
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
### ChromeOS
**INAV Configurator** form ChromeOS is available in [Chrome Web Store](https://chrome.google.com/webstore/detail/inav-configurator/fmaidjmgkdkpafmbnmigkpdnpdhopgel)
### Building and running INAV Configurator locally (for development or Linux users)
## Building and running INAV Configurator locally (for development or Linux users)
For local development, **node.js** build system is used.
@ -68,7 +76,13 @@ in the `./dist/` directory.
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.
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.
### Running with debug | Inspector
To be able to open Inspector, you will need SDK flavours of NW.js
`npm install nw@0.61.0 --nwjs_build_type=sdk`
## Different map providers
@ -103,15 +117,6 @@ INAV Configurator is shipped **WITHOUT** API key for Bing Maps. That means: ever
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
## Authors
Konstantin Sharlaimov/DigitalEntity - maintainer of the INAV firmware and configurator.
INAV Configurator was originally a [fork](#credits) of Cleanflight Configurator with support for INAV instead of Cleanflight.
This configurator is the only configurator with support for INAV specific features. It will likely require that you run the latest firmware on the flight controller.
If you are experiencing any problems please make sure you are running the [latest firmware version](https://github.com/iNavFlight/inav/releases).
## Notes
### WebGL
@ -123,14 +128,6 @@ Make sure Settings -> System -> "User hardware acceleration when available" is c
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
## Support
GitHub issue tracker is reserved for bugs and other technical problems. If you do not know how to setup
everything, hardware is not working or have any other _support_ problem, please consult:
* [rcgroups main thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
* [Telegram Group](https://t.me/INAVFlight)
## Issue trackers
For INAV configurator issues raise them here
@ -144,8 +141,3 @@ https://github.com/iNavFlight/inav/issues
## Developers
We accept clean and reasonable patches, submit them!
## Credits
ctn - primary author and maintainer of Baseflight Configurator.
Hydra - author and maintainer of Cleanflight Configurator from which this project was forked.

View file

@ -12,13 +12,16 @@
"options_improve_configurator": {
"message": "Send anonymous usage data to the developer team"
},
"options_showProfileParameters": {
"message": "Highlight parameters that change when switching battery or control profiles"
},
"options_unit_type": {
"message": "Set how the units render on the configurator only"
},
"options_render": {
"message": "Configurator rendering options"
},
"connect": {
"message": "Connect"
},
@ -109,15 +112,9 @@
"tabFailsafe": {
"message": "Failsafe"
},
"tabTransponder": {
"message": "Race Transponder"
},
"tabGPS": {
"message": "GPS"
},
"tabMagnetometer": {
"message": "Magnetometer"
},
"tabOutputs": {
"message": "Outputs"
},
@ -681,12 +678,6 @@
"featureCHANNEL_FORWARDING": {
"message": "Forward aux channels to servo outputs"
},
"featureTRANSPONDER": {
"message": "Race Transponder"
},
"featureTRANSPONDERTip": {
"message": "Configure via the Race Transponder tab after enabling."
},
"featureSOFTSPI": {
"message": "CPU based SPI"
},
@ -883,79 +874,79 @@
"message": "Fixed Wing Auto Launch Settings"
},
"configurationLaunchVelocity": {
"message": "Threshold Velocity [cm/s]"
"message": "Threshold Velocity"
},
"configurationLaunchVelocityHelp": {
"message": "Forward velocity threshold for swing-launch detection. Default: 300 [100-10000]"
},
"configurationLaunchAccel": {
"message": "Threshold Acceleration [cm/s/s]"
"message": "Threshold Acceleration"
},
"configurationLaunchAccelHelp": {
"message": "Forward acceleration threshold for bungee launch or throw launch, 1G = 981 cm/s/s. Default: 1863 [1000-20000]"
},
"configurationLaunchMaxAngle": {
"message": "Max Throw Angle [°]"
"message": "Max Throw Angle"
},
"configurationLaunchMaxAngleHelp": {
"message": "Max throw angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely. Default: 45 [5-180]"
},
"configurationLaunchDetectTime": {
"message": "Detect Time [ms]"
"message": "Detect Time"
},
"configurationLaunchDetectTimeHelp": {
"message": "Time for which thresholds have to breached to consider launch happened. Default: 40 [10-1000]"
},
"configurationLaunchThr": {
"message": "Launch Throttle [uS]"
"message": "Launch Throttle"
},
"configurationLaunchThrHelp": {
"message": "Launch throttle - throttle to be set during launch sequence. Default: 1700 [1000-2000]"
},
"configurationLaunchIdleThr": {
"message": "Idle Throttle [uS]"
"message": "Idle Throttle"
},
"configurationLaunchIdleThrHelp": {
"message": "Idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position). Default: 1000 [1000-2000]"
},
"configurationLaunchMotorDelay": {
"message": "Motor Delay [ms]"
"message": "Motor Delay"
},
"configurationLaunchMotorDelayHelp": {
"message": "Delay between detected launch and launch sequence start and throttling up. Default: 500 [0-5000]"
},
"configurationLaunchSpinupTime": {
"message": "Motor Spinup Time [ms]"
"message": "Motor Spinup Time"
},
"configurationLaunchSpinupTimeHelp": {
"message": "Time to bring power from minimum throttle to nav_fw_launch_thr, to avoid big stress on ESC and large torque from propeller. Default: 100 [0-1000]"
},
"configurationLaunchMinTime": {
"message": "Minimum Launch Time [ms]"
"message": "Minimum Launch Time"
},
"configurationLaunchMinTimeHelp": {
"message": "Allow launch mode to execute at least this time [ms] and ignore stick movements. Default: 0 [0-60000]"
},
"configurationLaunchTimeout": {
"message": "Launch Timeout [ms]"
"message": "Launch Timeout"
},
"configurationLaunchTimeoutHelp": {
"message": "Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over. Default: 5000 [0-60000]"
},
"configurationLaunchEndTime": {
"message": "End Transition Time [ms]"
"message": "End Transition Time"
},
"configurationLaunchEndTimeHelp": {
"message": "Smooth transition time at the end of the launch (ms). This is added to the Launch Timeout. Default: 2000 [0-5000]"
},
"configurationLaunchMaxAltitude": {
"message": "Maximum Altitude [cm]"
"message": "Maximum Altitude"
},
"configurationLaunchMaxAltitudeHelp": {
"message": "Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. Default: 0 [0-60000]"
},
"configurationLaunchClimbAngle": {
"message": "Climb Angle [°]"
"message": "Climb Angle"
},
"configurationLaunchClimbAngleHelp": {
"message": "Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit. Default: 18 [5-45]"
@ -985,7 +976,7 @@
"message": "Cycles/Sec (Hz)"
},
"configurationGPS": {
"message": "GPS"
"message": "Configuration"
},
"configurationGPSProtocol": {
"message": "Protocol"
@ -1161,79 +1152,238 @@
"portsFunction_IMU2": {
"message": "Secondary IMU"
},
"pidTuningName": {
"pidTuning_ShowAllPIDs": {
"message": "Show all PIDs"
},
"pidTuning_SelectNewDefaults": {
"message": "Select New Defaults"
},
"pidTuning_ResetPIDController": {
"message": "Reset PID Controller"
},
"pidTuning_PIDgains": {
"message" :"PID gains"
},
"pidTuning_Name": {
"message": "Name"
},
"pidTuningProportional": {
"pidTuning_Proportional": {
"message": "Proportional"
},
"pidTuningIntegral": {
"pidTuning_Integral": {
"message": "Integral"
},
"pidTuningDerivative": {
"pidTuning_Derivative": {
"message": "Derivative"
},
"pidTuningFeedForward": {
"pidTuning_FeedForward": {
"message": "FeedForward"
},
"pidTuningControlDerivative": {
"pidTuning_ControlDerivative": {
"message": "Control Derivative"
},
"pidTuningRollPitchRate": {
"pidTuning_Basic": {
"message": "Basic/Acro"
},
"pidTuning_Level": {
"message": "Angle/Horizon"
},
"pidTuning_Altitude": {
"message": "Barometer & Sonar/Altitude"
},
"pidTuning_Mag": {
"message": "Magnometer/Heading"
},
"pidTuning_GPS": {
"message": "GPS Navigation"
},
"pidTuning_LevelP": {
"message": "Strength"
},
"pidTuning_LevelI": {
"message": "LPF cutoff (Hz)"
},
"pidTuning_LevelD": {
"message": "Transition (Horizon)"
},
"pidTuning_LevelHelp": {
"message": "The values below change the behaviour of the ANGLE and HORIZON flight modes. Different PID controllers handle the LEVEL values differently. Please check the documentation."
},
"pidTuning_RatesAndExpo": {
"message": "Rates & Expo"
},
"pidTuning_RollPitchRate": {
"message": "ROLL & PITCH rate"
},
"pidTuningRollRate": {
"pidTuning_RollRate": {
"message": "ROLL rate"
},
"pidTuningPitchRate": {
"pidTuning_PitchRate": {
"message": "PITCH rate"
},
"pidTuningYawRate": {
"pidTuning_YawRate": {
"message": "YAW rate"
},
"pidTuningMaxRollAngle": {
"pidTuning_RollAndPitchExpo": {
"message": "Roll & Pitch Expo"
},
"pidTuning_YawExpo" : {
"message": "Yaw Expo"
},
"pidTuning_MaxRollAngle": {
"message": "Max. ROLL angle"
},
"pidTuningMaxRollAngleHelp": {
"pidTuning_MaxRollAngleHelp": {
"message": "Maximum ROLL angle in ANGLE mode. This also constrains the maximum bank in navigation modes."
},
"pidTuningMaxPitchAngle": {
"pidTuning_MaxPitchAngle": {
"message": "Max. PITCH angle"
},
"pidTuningMaxPitchAngleHelp": {
"pidTuning_MaxPitchAngleHelp": {
"message": "Maximum PITCH angle in ANGLE mode. This also constrains the maximum climb and dive in navigation modes."
},
"pidTuningManualRollRate": {
"pidTuning_ManualRollRate": {
"message": "Manual ROLL rate"
},
"pidTuningManualPitchRate": {
"pidTuning_ManualPitchRate": {
"message": "Manual PITCH rate"
},
"pidTuningManualYawRate": {
"pidTuning_ManualYawRate": {
"message": "Manual YAW rate"
},
"magHoldYawRate": {
"message": "MagHold rate"
"pidTuning_magHoldYawRate": {
"message": "Heading Hold rate limit"
},
"pidTuningMagHoldYawRateHelp": {
"pidTuning_MagHoldYawRateHelp": {
"message": "Maximum YAW rotation rate that MagHold controller can request from UAV. Used only when MagHold mode is enabled, during RTH and WAYPOINT navigation. Values below 30dps gives nice \"cinematic\" turns"
},
"pidTuningTPA": {
"pidTuning_Filters": {
"message": "Filters"
},
"pidTuning_mainFilters": {
"message": "Gyro filters"
},
"pidTuning_gyro_main_lpf_hz": {
"message": "Main gyro filter cutoff frequency"
},
"pidTuning_gyro_main_lpf_hz_help": {
"message": "Higher values offer lower delay but more noise. Lower values offer less noise, but more dalay on the gyro processing"
},
"pidTuning_MatrixFilterMinFrequency": {
"message": "Matrix Filter Min Frequency"
},
"pidTuning_MatrixFilterMinFrequencyHelp": {
"message": "Minimum frequency for the Matrix Filter. Value should depends on propeller size. 150Hz work fine with 5" and smaller. For 7" and above lower even below 100Hz."
},
"pidTuning_MatrixFilterQFactor": {
"message": "Matrix Filter Q Factor"
},
"pidTuning_MatrixFilterQFactorHelp": {
"message": "The higher value, the higher selectivity of the Matrix Filter. Values between 150 and 300 are recommended."
},
"pidTuning_UnicornFilterQFactor": {
"message": "Unicorn Filter Q Factor"
},
"pidTuning_dtermFilters": {
"message": "D-term filters"
},
"pidTuning_dtermLpfCutoffFrequency": {
"message": "D-term LPF cutoff frequency"
},
"pidTuning_dtermLpfCutoffFrequencyHelp": {
"message": "Lowpass cutoff filter for Dterm for all PID controllers"
},
"pidTuning_rpmFilters": {
"message": "Gyro RPM filters"
},
"pidTuning_rpm_gyro_filter_enabled": {
"message": "Gyro RPM filter (requires ESC telemetry)"
},
"pidTuning_rpm_gyro_min_hz": {
"message": "Gyro RPM filter min. frequency"
},
"pidTuning_Mechanics": {
"message": "Mechanics"
},
"pidTuning_ITermMechanics": {
"message": "I-term mechanics"
},
"pidTuning_itermRelaxCutoff": {
"message": "Iterm Relax Cutoff Frequency"
},
"pidTuning_itermRelaxCutoffHelp": {
"message": "Lower values open a longer time window for Iterm Relax to work on and stronger Iterm suppression. Higher values shortens the time windows and reduces suppression."
},
"pidTuning_antigravityGain": {
"message": "Antigravity Gain"
},
"pidTuning_antigravityAccelerator": {
"message": "Antigravity Accelerator"
},
"pidTuning_antigravityCutoff": {
"message": "Antigravity Cutoff Frequency"
},
"pidTuning_itermBankAngleFreeze": {
"message": "Yaw Iterm freeze bank angle"
},
"pidTuning_itermBankAngleFreezeHelp": {
"message": "Freeze yaw Iterm when plane is banked more than this many degrees. This helps to stop the rudder from counteracting turn. 0 disables this feature. Applies only to fixed wing aircraft."
},
"pidTuning_dTermMechanics": {
"message": "D-term mechanics"
},
"pidTuning_d_boost_min": {
"message": "D-Boost Min. Scale"
},
"pidTuning_d_boost_min_help": {
"message": "Defines the max allowed Dterm attenuation during stick acceleration phase. Value 1.0 mean Dterm is not attenuate. 0.5 mean it's allowed to shrink by half. Lower values result in faster response during fast stick movement."
},
"pidTuning_d_boost_max": {
"message": "D-Boost Max. Scale"
},
"pidTuning_d_boost_max_help": {
"message": "Defines the maximum Dterm boost when maximum angular acceleration is reached. 1.0 means D-Boost is disabled, 2.0 means Dterm is allowed to grow by 100%. Values between 1.5 and 1.7 are usually the sweet spot."
},
"pidTuning_d_boost_max_at_acceleration": {
"message": "Top D-Boost at acceleration [dps^2]"
},
"pidTuning_d_boost_max_at_acceleration_help": {
"message": "D-Boost is fully active when angular acceleration (either detected by gyro or rate target) reached given acceleration. Between 0 and this value, D-Boost factor is scaled lineary"
},
"pidTuning_d_boost_gyro_delta_lpf_hz": {
"message": "D-Boost gyro LPF"
},
"pidTuning_d_boost_gyro_delta_lpf_hz_help": {
"message": "Should be set to the frequency of propeller wash oscillations. 5-inch quads work best at around 80Hz, 7-inch quads at around 50Hz"
},
"pidTuning_tpaMechanics": {
"message": "Thrust PID attenuation"
},
"pidTuning_TPA": {
"message": "Thrust PID Attenuation (TPA)"
},
"pidTuningTPABreakPoint": {
"pidTuning_TPABreakPoint": {
"message": "TPA Breakpoint"
},
"pidTuningButtonSave": {
"pidTuning_fwLevelTrimMechanics": {
"message": "Fixed Wing Level Trim"
},
"pidTuning_fw_level_pitch_trim": {
"message": "Level Trim [deg]"
},
"pidTuning_fw_level_pitch_trim_help": {
"message": "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
},
"pidTuning_ButtonSave": {
"message": "Save"
},
"pidTuningButtonRefresh": {
"pidTuning_ButtonRefresh": {
"message": "Refresh"
},
"pidTuningProfileHead": {
"pidTuning_ProfileHead": {
"message": "Profile"
},
"pidTuningLoadedProfile": {
"pidTuning_LoadedProfile": {
"message": "Loaded Profile: <strong style=\"color: #37a8db\">$1</strong>"
},
"loadedBatteryProfile": {
@ -1560,33 +1710,6 @@
"programmingEepromSaved": {
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Programming"
},
"transponderNotSupported": {
"message": "Your flight controller's firmware does not support transponder functionality."
},
"transponderHelp": {
"message": "Configure your transponder code here. Note: Only valid codes will be recognised by race timing systems. Valid transponder codes can be obtained from <a href=\"http://seriouslypro.com/transponder-codes\" target=\"_blank\">Seriously Pro</a>."
},
"transponderInformation": {
"message": "Transponders systems allow race organizers to time your laps. The transponder is fitted to your aircraft and when your aircraft passes the timing gate the track-side receiver registers your code and records your laptime. When fitting an IR based transponder your should ensure that it points outward from your aircraft towards the track-side receivers and that the light beam is not obstructed by your airframe, battery-straps, cables, propellers, etc."
},
"transponderConfiguration": {
"message": "Configuration"
},
"transponderData": {
"message": "Data"
},
"transponderDataHelp": {
"message": "Hexadecimal digits only, 0-9, A-F"
},
"transponderButtonSave": {
"message": "Save"
},
"transponderDataInvalid": {
"message": "Transponder data is <span style=\"color: red\">invalid</span>"
},
"transponderEepromSaved": {
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Transponder"
},
"servosChangeDirection": {
"message": "Change Direction in TX To Match"
},
@ -1636,10 +1759,10 @@
"message":"<ol><li>Remove propellers</li><li>Connect LiPo and use Outputs Tab to test all motors</li><li>Note the position of each motor (motor #1 - Left Top and so on)</li><li>Fill the table below</li></ol>"
},
"gpsHead": {
"message": "GPS"
"message": "Position"
},
"gpsStatHead": {
"message": "GPS Statistics"
"message": "Statistics"
},
"gpsMapHead": {
"message": "Current GPS location"
@ -1781,6 +1904,15 @@
"cliCopyToClipboardBtn": {
"message": "Copy to clipboard"
},
"cliExitBtn": {
"message": "EXIT"
},
"cliSaveSettingsBtn": {
"message": "SAVE SETTINGS"
},
"cliMscBtn": {
"message": "MSC"
},
"cliCopySuccessful": {
"message": "Copied!"
},
@ -2080,33 +2212,6 @@
"radioChannelShort": {
"message": "CH "
},
"pidTuningBasic": {
"message": "Basic/Acro"
},
"pidTuningLevel": {
"message": "Angle/Horizon"
},
"pidTuningAltitude": {
"message": "Barometer & Sonar/Altitude"
},
"pidTuningMag": {
"message": "Magnometer/Heading"
},
"pidTuningGps": {
"message": "GPS Navigation"
},
"pidTuningLevelP": {
"message": "Strength"
},
"pidTuningLevelI": {
"message": "LPF cutoff (Hz)"
},
"pidTuningLevelD": {
"message": "Transition (Horizon)"
},
"pidTuningLevelHelp": {
"message": "The values below change the behaviour of the ANGLE and HORIZON flight modes. Different PID controllers handle the LEVEL values differently. Please check the documentation."
},
"configHelp2": {
"message": "Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc. When running external sensors, use the sensor alignments (Gyro, Acc, Mag) to define sensor position independent from board orientation. "
},
@ -2159,7 +2264,7 @@
"message": "<strong>Note:</strong> When Stage 2 is DISABLED, the fallback setting <strong>Auto</strong> is used instead of the user settings for all flightchannels (Roll, Pitch, Yaw and Throttle)."
},
"failsafeDelayItem": {
"message": "Guard time for activation after signal lost [1 = 0.1 sec.]"
"message": "Guard time for activation after signal lost [For deciseconds (ds): 1 = 0.1 sec.]"
},
"failsafeDelayHelp": {
"message": "Time for stage 1 to wait for recovery"
@ -2168,7 +2273,7 @@
"message": "Throttle value used while landing"
},
"failsafeOffDelayItem": {
"message": "Delay for turning off the Motors during Failsafe [1 = 0.1 sec.]"
"message": "Delay for turning off the Motors during Failsafe [For deciseconds (ds):1 = 0.1 sec.]"
},
"failsafeOffDelayHelp": {
"message": "Time to stay in landing mode untill the motors are turned off and the craft is disarmed"
@ -2278,12 +2383,6 @@
"accLpfCutoffFrequency": {
"message": "Accelerometer LPF cutoff frequency"
},
"dtermLpfCutoffFrequency": {
"message": "D-term LPF cutoff frequency"
},
"dtermLpfCutoffFrequencyHelp": {
"message": "Lowpass cutoff filter for Dterm for all PID controllers"
},
"yawLpfCutoffFrequency": {
"message": "Yaw LPF cutoff frequency"
},
@ -2543,16 +2642,16 @@
"message": "User Control Mode"
},
"posholdDefaultSpeed": {
"message": "Default navigation speed [cm/s]"
"message": "Default navigation speed"
},
"posholdDefaultSpeedHelp": {
"message": "Default speed during RTH, also used for WP navigation if no speed set for WP leg. Limited to Max. navigation speed"
},
"posholdMaxSpeed": {
"message": "Max. navigation speed [cm/s]"
"message": "Max. navigation speed"
},
"posholdMaxManualSpeed": {
"message": "Max. CRUISE speed [cm/s]"
"message": "Max. CRUISE speed"
},
"posholdMaxManualSpeedHelp": {
"message": "Maximum horizonal velocity allowed for pilot manual control during POSHOLD/CRUISE mode"
@ -2564,7 +2663,7 @@
"message": "Max. ALTHOLD climb rate [cm/s]"
},
"posholdMaxBankAngle": {
"message": "Multirotor max. banking angle [degrees]"
"message": "Multirotor max. banking angle"
},
"posholdMaxBankAngleHelp": {
"message": "Maximum banking angle in navigation modes. Constrained by maximum ROLL angle in PID tuning tab."
@ -2621,7 +2720,7 @@
"message": "Automatic landing settings"
},
"minRthDistance": {
"message": "Min. RTH distance [cm]"
"message": "Min. RTH distance"
},
"minRthDistanceHelp": {
"message": "If UAV is within this distance from the home point, it will land instead of RTH then land"
@ -2651,46 +2750,46 @@
"message": "RTH altitude mode"
},
"rthAbortThreshold": {
"message": "RTH abort threshold [cm]"
"message": "RTH abort threshold"
},
"rthAbortThresholdHelp": {
"message": "RTH sanity checking feature will notice if the distance to home is increasing during RTH and if it exceeds the threshold defined by this parameter, instead of continuing RTH the UAV will enter emergency landing. Default is 500m which is safe enough for both multirotors and airplanes."
},
"rthAltitude": {
"message": "RTH altitude [cm]"
"message": "RTH altitude"
},
"rthAltitudeHelp": {
"message": "Used in Extra, Fixed and 'At Least' RTH altitude modes"
},
"rthHomeAltitudeLabel": {
"message": "RTH Home altitude [cm]"
"message": "RTH Home altitude"
},
"rthHomeAltitudeHelp": {
"message": "Used when not landing at the home point. Upon arriving at home, the plane will loiter and change altitude to the RTH Home Altitude. Default is 0, which is feature disabled."
},
"landMaxAltVspd": {
"message": "<strong>Initial landing speed</strong> until <strong>Slow down altitude</strong> is reached"
"message": "The craft will start to descend at this speed, once it reaches the <strong>Home</strong> location."
},
"landMaxAltVspdHelp": {
"message": "After RTH if autolanding is enabled the aircraft will start to descend at this speed until reaching <strong>Slow down altitude</strong>"
},
"landSlowdownMaxAlt": {
"message": "<strong>Slow down altitude</strong>. Altitude bellow which the aircraft will start to slow down"
"message": "When the craft has descended to <i>this</i> altitude. It will begin to slow down for landing."
},
"landSlowdownMaxAltHelp": {
"message": "When the aircraft reaches this altitude it will start to slow down linearly between the <strong>Initial landing speed</strong> and <strong>Final landing speed</strong> to reach it at <strong>Final approach altitude</strong>"
},
"landSlowdownMinAlt": {
"message": "When the craft has descended to <i>this</i> altitude, it will have slowed to the touch down speed."
},
"landMinAltVspd": {
"message": "<strong>Final landing speed</strong>. Speed the aircraft will take until touchdown when the <strong>Final approach altitutde</strong> is reached"
"message": "This is the touch down speed."
},
"landMinAltVspdHelp": {
"message": "The aircraft vertical speed target will be this value when the aircraft reaches the <strong>Final approach altitude</strong> after having slowed down linearly from the <strong>Slow down altitude</strong> at <strong>Initial landing speed</strong>"
},
"landSlowdownMinAlt": {
"message": "<strong>Final approach altitude</strong>. Altitude under which the aircraft will go down at <strong>Final landing speed</strong> until touchdown"
},
"emergencyDescentRate": {
"message": "Emergency landing speed [cm/s]"
"message": "Emergency landing speed"
},
"cruiseThrottle": {
"message": "Cruise throttle"
@ -2714,31 +2813,31 @@
"message": "Max. throttle"
},
"maxBankAngle": {
"message": "Max. navigation bank angle [degrees]"
"message": "Max. navigation bank angle"
},
"maxBankAngleHelp": {
"message": "Maximum banking angle in navigation modes. Constrained by maximum ROLL angle in PID tuning tab."
},
"maxClimbAngle": {
"message": "Max. navigation climb angle [degrees]"
"message": "Max. navigation climb angle"
},
"maxClimbAngleHelp": {
"message": "Maximum climb angle in navigation modes. Constrained by maximum PITCH angle in PID tuning tab."
},
"navManualClimbRate": {
"message": "Max. Alt-hold climb rate [cm/s]"
"message": "Max. Alt-hold climb rate"
},
"navManualClimbRateHelp": {
"message": "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
},
"navAutoClimbRate": {
"message": "Max. navigation climb rate [cm/s]"
"message": "Max. navigation climb rate"
},
"navAutoClimbRateHelp": {
"message": "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
},
"maxDiveAngle": {
"message": "Max. navigation dive angle [degrees]"
"message": "Max. navigation dive angle"
},
"maxDiveAngleHelp": {
"message": "Maximum dive angle in navigation modes. Constrained by maximum PITCH angle in PID tuning tab."
@ -2756,13 +2855,13 @@
"message": "How smoothly the autopilot adjusts the throttle level in response to pitch angle changes [0-9]."
},
"pitchToThrottleThreshold": {
"message": "Instantaneous throttle adjustment threshold [centidegrees]"
"message": "Instantaneous throttle adjustment threshold"
},
"pitchToThrottleThresholdHelp": {
"message": "The autopilot will instantly adjust the throttle level without smoothing according to pitch to throttle if the pitch angle is more this many centidegrees from the filtered value."
},
"loiterRadius": {
"message": "Loiter radius [cm]"
"message": "Loiter radius"
},
"loiterDirectionLabel": {
"message": "Loiter direction"
@ -2780,25 +2879,25 @@
"message": "Battery Estimation Settings"
},
"idlePower": {
"message": "Idle power [cW]"
"message": "Idle power"
},
"idlePowerHelp": {
"message": "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
},
"cruisePower": {
"message": "Cruise power [cW]"
"message": "Cruise power"
},
"cruisePowerHelp": {
"message": "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
},
"cruiseSpeed": {
"message": "Cruise speed [cm/s]"
"message": "Cruise speed"
},
"cruiseSpeedHelp": {
"message": "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
},
"rthEnergyMargin": {
"message": "RTH energy margin [%]"
"message": "RTH energy margin"
},
"rthEnergyMarginHelp": {
"message": "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation."
@ -2810,13 +2909,13 @@
"message": "Waypoint Navigation Settings"
},
"waypointRadius": {
"message": "Waypoint radius [cm]"
"message": "Waypoint radius"
},
"waypointRadiusHelp": {
"message": "This sets the distance away from a waypoint that triggers the waypoint as reached."
},
"waypointSafeDistance": {
"message": "Waypoint safe distance [cm]."
"message": "Waypoint safe distance"
},
"waypointSafeDistanceHelp": {
"message": "The maximum distance between the home point and the first waypoint."
@ -2927,16 +3026,16 @@
"message": "Fly Time (minutes)"
},
"osd_alt_alarm": {
"message": "Altitude (meters)"
"message": "Altitude"
},
"osd_dist_alarm": {
"message": "Distance (meters)"
"message": "Distance"
},
"osdAlarmDIST_HELP": {
"message": "The distance to home indicator will flash when the distance is greater than this value. Zero disables this alarm."
},
"osd_neg_alt_alarm": {
"message": "Negative Altitude (meters)"
"message": "Negative Altitude"
},
"osdAlarmMAX_NEG_ALTITUDE_HELP": {
"message": "The altitude indicator will flash when altitude is negative and its absolute value is greater than this alarm. Useful when taking off from elevated places. Zero disables this alarm."
@ -3610,9 +3709,15 @@
"mixerPreset": {
"message": "Mixer preset"
},
"mixerNotLoaded": {
"message": "Mixer not loaded.<br />Click <b>Load and apply</b> or <b>Load mixer</b> to use the selected mixer.<br />Or click <b>Refresh mixer</b> to use your current mixer."
},
"mixerLoadPresetRules": {
"message": "Load mixer"
},
"mixerRefreshCurrentRules": {
"message": "Refresh mixer"
},
"mixerLoadAndApplyPresetRules": {
"message": "Load and apply"
},
@ -3682,6 +3787,12 @@
"confirm_reset_settings": {
"message": "Do you really want to reset all settings?\nATTENTION: All settings are lost! You have to setup the whole aircraft after this operation!"
},
"confirm_select_defaults": {
"message": "This will allow to select new default values for all settings. Existing PID tune and other settings might be lost!\nDo you want to continue?"
},
"confirm_reset_pid": {
"message": "This will reset all PID settings to firmware default values and save.\nDo you want to continue?"
},
"mappingTableOutput": {
"message": "Output"
},
@ -3710,49 +3821,49 @@
"message": "Distance to home"
},
"brakingSpeedThreshold": {
"message": "Min. speed threshold [cm/s]"
"message": "Min. speed threshold"
},
"brakingSpeedThresholdTip": {
"message": "Braking will be enabled only if actual speed if higher than threshold"
},
"brakingDisengageSpeed": {
"message": "Braking disengage speed [cm/s]"
"message": "Braking disengage speed"
},
"brakingDisengageSpeedTip": {
"message": "Braking will end when speed goes below this value"
},
"brakingTimeout": {
"message": "Max. braking duration [ms]"
"message": "Max. braking duration"
},
"brakingTimeoutTip": {
"message": "Safety measure. This is the longest period of time braking can be active."
},
"brakingBoostFactor": {
"message": "Boost factor [%]"
"message": "Boost factor"
},
"brakingBoostFactorTip": {
"message": "Defines how strong the braking boost will be. 100% means the navigation engine is allowed to double the banking speed and acceleration"
},
"brakingBoostTimeout": {
"message": "Max. braking boost duration [ms]"
"message": "Max. braking boost duration"
},
"brakingBoostTimeoutTip": {
"message": "Safety measure. This is the longest period of time braking boost can be active."
},
"brakingBoostSpeedThreshold": {
"message": "Boost min. speed threshold [cm/s]"
"message": "Boost min. speed threshold"
},
"brakingBoostSpeedThresholdTip": {
"message": "Braking boost will be enabled only if actual speed if higher than threshold"
},
"brakingBoostDisengageSpeed": {
"message": "Braking boost disengage speed [cm/s]"
"message": "Braking boost disengage speed"
},
"brakingBoostDisengageSpeedTip": {
"message": "Braking boost will end when speed goes below this value"
},
"brakingBankAngle": {
"message": "Max. bank angle [degrees]"
"message": "Max. bank angle"
},
"brakingBankAngleTip": {
"message": "Max bank angle allowed during braking phase"
@ -3859,18 +3970,6 @@
"itermRelaxHelp": {
"message": "Defines Iterm relaxation algorithm activation. PR mean it's active on Roll and Pitch axis. PRY is active also on Yaw."
},
"itermRelaxCutoff": {
"message": "Iterm Relax Cutoff Frequency"
},
"itermRelaxCutoffHelp": {
"message": "Lower values open a longer time window for Iterm Relax to work on and stronger Iterm suppression. Higher values shortens the time windows and reduces suppression."
},
"gyro_main_lpf_hz": {
"message": "Main gyro filter cutoff frequency"
},
"gyro_main_lpf_hz_help": {
"message": "Higher values offer lower delay but more noise. Lower values offer less noise, but more dalay on the gyro processing"
},
"gyro_main_lpf_type": {
"message": "Gyro LPF type"
},
@ -3898,81 +3997,9 @@
"tabFilteringAdvanced": {
"message": "Other filters"
},
"mainFilters": {
"message": "Gyro filters"
},
"rpmFilters": {
"message": "Gyro RPM filters"
},
"dtermFilters": {
"message": "D-term filters"
},
"rpm_gyro_filter_enabled": {
"message": "Gyro RPM filter (requires ESC telemetry)"
},
"rpm_gyro_min_hz": {
"message": "Gyro RPM filter min. frequency"
},
"dTermMechanics": {
"message": "D-term mechanics"
},
"tpaMechanics": {
"message": "Thrust PID attenuation"
},
"fw_level_pitch_trim": {
"message": "Level Trim [deg]"
},
"fw_level_pitch_trim_help": {
"message": "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
},
"fwLevelTrimMechanics": {
"message": "Fixed Wing Level Trim"
},
"d_boost_min": {
"message": "D-Boost Min. Scale"
},
"d_boost_min_help": {
"message": "Defines the max allowed Dterm attenuation during stick acceleration phase. Value 1.0 mean Dterm is not attenuate. 0.5 mean it's allowed to shrink by half. Lower values result in faster response during fast stick movement."
},
"d_boost_max": {
"message": "D-Boost Max. Scale"
},
"d_boost_max_help": {
"message": "Defines the maximum Dterm boost when maximum angular acceleration is reached. 1.0 means D-Boost is disabled, 2.0 means Dterm is allowed to grow by 100%. Values between 1.5 and 1.7 are usually the sweet spot."
},
"d_boost_max_at_acceleration": {
"message": "Top D-Boost at acceleration [dps^2]"
},
"d_boost_max_at_acceleration_help": {
"message": "D-Boost is fully active when angular acceleration (either detected by gyro or rate target) reached given acceleration. Between 0 and this value, D-Boost factor is scaled lineary"
},
"d_boost_gyro_delta_lpf_hz": {
"message": "D-Boost gyro LPF"
},
"d_boost_gyro_delta_lpf_hz_help": {
"message": "Should be set to the frequency of propeller wash oscillations. 5-inch quads work best at around 80Hz, 7-inch quads at around 50Hz"
},
"iTermMechanics": {
"message": "I-term mechanics"
},
"gps_map_center": {
"message": "Center"
},
"antigravityGain": {
"message": "Antigravity Gain"
},
"antigravityAccelerator": {
"message": "Antigravity Accelerator"
},
"antigravityCutoff": {
"message": "Antigravity Cutoff Frequency"
},
"itermBankAngleFreeze": {
"message": "Yaw Iterm freeze bank angle"
},
"itermBankAngleFreezeHelp": {
"message": "Freeze yaw Iterm when plane is banked more than this many degrees. This helps to stop the rudder from counteracting turn. 0 disables this feature. Applies only to fixed wing aircraft."
},
"ouptputsConfiguration": {
"message": "Configuration"
},
@ -4134,5 +4161,44 @@
},
"reset": {
"message": "Reset"
},
"illegalStateRestartRequired": {
"message": "Illegal state. Restart required."
},
"motor_direction_inverted": {
"message": "Reversed motor direction / Props In configuration"
},
"motor_direction_inverted_hint": {
"message": "Enable if the motor direction is reversed and the props are mounted in the opposite direction."
},
"blackboxFields": {
"message": "Blackbox fields"
},
"BLACKBOX_FEATURE_NAV_ACC": {
"message": "Navigation accelerometer"
},
"BLACKBOX_FEATURE_NAV_POS": {
"message": "Navigation position estimation"
},
"BLACKBOX_FEATURE_NAV_PID": {
"message": "Navigation PID"
},
"BLACKBOX_FEATURE_MAG": {
"message": "Magnetometer"
},
"BLACKBOX_FEATURE_ACC": {
"message": "Accelerometer"
},
"BLACKBOX_FEATURE_ATTITUDE": {
"message": "Attitude"
},
"BLACKBOX_FEATURE_RC_DATA": {
"message": "RC data"
},
"BLACKBOX_FEATURE_RC_COMMAND": {
"message": "RC command"
},
"BLACKBOX_FEATURE_MOTORS": {
"message": "Motors output"
}
}

View file

@ -1,4 +1,4 @@
/*global mspHelper,$,GUI,MSP,BF_CONFIG,chrome*/
/*global mspHelper,$,GUI,MSP,chrome*/
'use strict';
var helper = helper || {};
@ -16,7 +16,12 @@ helper.defaultsDialog = (function () {
"id": 2,
"notRecommended": false,
"reboot": true,
"mixerToApply": 3,
"settings": [
{
key: "model_preview_type",
value: 3
},
/*
System
*/
@ -198,7 +203,12 @@ helper.defaultsDialog = (function () {
"notRecommended": false,
"id": 3,
"reboot": true,
"mixerToApply": 14,
"settings": [
{
key: "model_preview_type",
value: 14
},
{
key: "platform_type",
value: "AIRPLANE"
@ -392,7 +402,12 @@ helper.defaultsDialog = (function () {
"notRecommended": false,
"id": 3,
"reboot": true,
"mixerToApply": 8,
"settings": [
{
key: "model_preview_type",
value: 8
},
{
key: "platform_type",
value: "AIRPLANE"
@ -586,7 +601,12 @@ helper.defaultsDialog = (function () {
"id": 1,
"notRecommended": false,
"reboot": true,
"mixerToApply": 31,
"settings": [
{
key: "model_preview_type",
value: 31
},
{
key: "gyro_hardware_lpf",
value: "256HZ"
@ -685,6 +705,24 @@ helper.defaultsDialog = (function () {
}
};
privateScope.finalize = function (selectedDefaultPreset) {
mspHelper.saveToEeprom(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
if (selectedDefaultPreset.reboot) {
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
//noinspection JSUnresolvedVariable
savingDefaultsModal.close();
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
}
});
};
privateScope.setSettings = function (selectedDefaultPreset) {
//Save analytics
googleAnalytics.sendEvent('Setting', 'Defaults', selectedDefaultPreset.title);
@ -694,21 +732,30 @@ helper.defaultsDialog = (function () {
Promise.mapSeries(selectedDefaultPreset.settings, function (input, ii) {
return mspHelper.setSetting(input.key, input.value);
}).then(function () {
mspHelper.saveToEeprom(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
if (selectedDefaultPreset.reboot) {
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
//noinspection JSUnresolvedVariable
savingDefaultsModal.close();
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
}
});
// If default preset is associated to a mixer, apply the mixer as well
if (selectedDefaultPreset.mixerToApply) {
let currentMixerPreset = helper.mixer.getById(selectedDefaultPreset.mixerToApply);
helper.mixer.loadServoRules(currentMixerPreset);
helper.mixer.loadMotorRules(currentMixerPreset);
SERVO_RULES.cleanup();
SERVO_RULES.inflate();
MOTOR_RULES.cleanup();
MOTOR_RULES.inflate();
mspHelper.sendServoMixer(function () {
mspHelper.sendMotorMixer(function () {
privateScope.finalize(selectedDefaultPreset);
})
});
} else {
privateScope.finalize(selectedDefaultPreset);
}
})
});
};
@ -733,7 +780,7 @@ helper.defaultsDialog = (function () {
savingDefaultsModal.close();
}
mspHelper.loadBfConfig(function () {
mspHelper.loadFeatures(function () {
privateScope.setFeaturesBits(selectedDefaultPreset)
});
} else {

592
js/fc.js
View file

@ -2,7 +2,6 @@
// define all the global variables that are uses to hold FC state
var CONFIG,
BF_CONFIG,
LED_STRIP,
LED_COLORS,
LED_MODE_COLORS,
@ -39,7 +38,6 @@ var CONFIG,
DATAFLASH,
SDCARD,
BLACKBOX,
TRANSPONDER,
RC_deadband,
SENSOR_ALIGNMENT,
RX_CONFIG,
@ -63,9 +61,13 @@ var CONFIG,
OUTPUT_MAPPING,
SETTINGS,
BRAKING_CONFIG,
SAFEHOMES;
SAFEHOMES,
BOARD_ALIGNMENT,
CURRENT_METER_CONFIG,
FEATURES;
var FC = {
restartRequired: false,
MAX_SERVO_RATE: 125,
MIN_SERVO_RATE: 0,
isAirplane: function () {
@ -75,14 +77,11 @@ var FC = {
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
},
isRpyFfComponentUsed: function () {
return (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE || MIXER_CONFIG.platformType == PLATFORM_ROVER || MIXER_CONFIG.platformType == PLATFORM_BOAT) || ((MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) && semver.gte(CONFIG.flightControllerVersion, "2.6.0"));
return true; // Currently all planes have roll, pitch and yaw FF
},
isRpyDComponentUsed: function () {
return true; // Currently all platforms use D term
},
isCdComponentUsed: function () {
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
},
resetState: function () {
SENSOR_STATUS = {
isHardwareHealthy: 0,
@ -127,21 +126,25 @@ var FC = {
name: ''
};
BF_CONFIG = {
mixerConfiguration: 0,
features: 0,
serialrx_type: 0,
board_align_roll: 0,
board_align_pitch: 0,
board_align_yaw: 0,
currentscale: 0,
currentoffset: 0
BOARD_ALIGNMENT = {
roll: 0,
pitch: 0,
yaw: 0
};
CURRENT_METER_CONFIG = {
scale: 0,
offset: 0,
type: 0,
capacity: 0
};
LED_STRIP = [];
LED_COLORS = [];
LED_MODE_COLORS = [];
FEATURES = 0;
PID = {
};
@ -246,23 +249,6 @@ var FC = {
packetCount: 0
};
/* MISSION_PLANNER = {
maxWaypoints: 0,
isValidMission: 0,
countBusyPoints: 0,
bufferPoint: {
number: 0,
action: 0,
lat: 0,
lon: 0,
alt: 0,
endMission: 0,
p1: 0,
p2: 0,
p3: 0
}
}; */
MISSION_PLANNER = new WaypointCollection();
ANALOG = {
@ -473,11 +459,6 @@ var FC = {
blackboxRateDenom: 1
};
TRANSPONDER = {
supported: false,
data: []
};
RC_deadband = {
deadband: 0,
yaw_deadband: 0,
@ -576,7 +557,7 @@ var FC = {
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
{bit: 4, group: 'other', name: 'MOTOR_STOP'},
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
{bit: 7, group: 'gps', name: 'GPS', haveTip: true},
{bit: 7, group: 'other', name: 'GPS', haveTip: true},
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'},
{bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true},
@ -595,10 +576,6 @@ var FC = {
{bit: 31, group: 'other', name: "FW_AUTOTRIM", haveTip: true, showNameInTip: true}
];
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0") && semver.lt(CONFIG.flightControllerVersion, "2.5.0")) {
features.push({bit: 5, group: 'other', name: 'DYNAMIC_FILTERS', haveTip: true, showNameInTip: true});
}
return features.reverse();
},
isFeatureEnabled: function (featureName, features) {
@ -606,7 +583,7 @@ var FC = {
features = this.getFeatures();
}
for (var i = 0; i < features.length; i++) {
if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) {
if (features[i].name == featureName && bit_check(FEATURES, features[i].bit)) {
return true;
}
}
@ -658,168 +635,69 @@ var FC = {
];
},
getEscProtocols: function () {
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
return {
0: {
name: "STANDARD",
message: null,
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
message: null,
defaultRate: 1000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "MULTISHOT",
message: null,
defaultRate: 2000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
},
3: {
name: "BRUSHED",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
},
4: {
name: "DSHOT150",
message: null,
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
5: {
name: "DSHOT300",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz"
}
},
6: {
name: "DSHOT600",
message: null,
defaultRate: 16000,
rates: {
16000: "16kHz"
}
return {
0: {
name: "STANDARD",
message: null,
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
};
} else {
return {
0: {
name: "STANDARD",
message: null,
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
message: null,
defaultRate: 1000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "ONESHOT42",
message: null,
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
3: {
name: "MULTISHOT",
message: null,
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
4: {
name: "BRUSHED",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
},
5: {
name: "DSHOT150",
message: null,
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
6: {
name: "DSHOT300",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz"
}
},
7: {
name: "DSHOT600",
message: null,
defaultRate: 16000,
rates: {
16000: "16kHz"
}
},
8: {
name: "DSHOT1200",
message: "escProtocolNotAdvised",
defaultRate: 16000,
rates: {
16000: "16kHz"
}
},
9: {
name: "SERIALSHOT",
message: "escProtocolExperimental",
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
1: {
name: "ONESHOT125",
message: null,
defaultRate: 1000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
};
}
},
2: {
name: "MULTISHOT",
message: null,
defaultRate: 2000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
},
3: {
name: "BRUSHED",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
},
4: {
name: "DSHOT150",
message: null,
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
5: {
name: "DSHOT300",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz"
}
},
6: {
name: "DSHOT600",
message: null,
defaultRate: 16000,
rates: {
16000: "16kHz"
}
}
};
},
getServoRates: function () {
return {
@ -860,37 +738,6 @@ var FC = {
getOsdDisabledFields: function () {
return [];
},
getAccelerometerNames: function () {
return [ "NONE", "AUTO", "MPU6050", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
},
getBarometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "MSP", "FAKE"];
} else {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"];
}
},
getPitotNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"];
} else {
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
}
},
getRangefinderNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
return [ "NONE", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "Benewake TFmini", "VL53L1X", "US42"];
} else {
return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
}
},
getOpticalFlowNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.7.0")) {
return [ "NONE", "CXOF", "MSP", "FAKE" ];
} else {
return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
}
},
getArmingFlags: function () {
return {
0: "OK_TO_ARM",
@ -927,7 +774,7 @@ var FC = {
]
},
getPidNames: function () {
let list = [
return [
'Roll',
'Pitch',
'Yaw',
@ -937,14 +784,9 @@ var FC = {
'Surface',
'Level',
'Heading Hold',
'Velocity Z'
'Velocity Z',
'Nav Heading'
];
if (semver.gte(CONFIG.flightControllerVersion, '2.5.0')) {
list.push("Nav Heading")
}
return list;
},
getRthAltControlMode: function () {
return ["Current", "Extra", "Fixed", "Max", "At least", "At least, linear descent"];
@ -1045,222 +887,266 @@ var FC = {
return {
0: {
name: "True",
operandType: "Active",
hasOperand: [false, false],
output: "boolean"
},
1: {
name: "Equal",
operandType: "Comparison",
hasOperand: [true, true],
output: "boolean"
},
2: {
name: "Greater Than",
operandType: "Comparison",
hasOperand: [true, true],
output: "boolean"
},
3: {
name: "Lower Than",
operandType: "Comparison",
hasOperand: [true, true],
output: "boolean"
},
4: {
name: "Low",
operandType: "RC Switch Check",
hasOperand: [true, false],
output: "boolean"
},
5: {
name: "Mid",
operandType: "RC Switch Check",
hasOperand: [true, false],
output: "boolean"
},
6: {
name: "High",
operandType: "RC Switch Check",
hasOperand: [true, false],
output: "boolean"
},
7: {
name: "AND",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
8: {
name: "OR",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
9: {
name: "XOR",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
10: {
name: "NAND",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
11: {
name: "NOR",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
12: {
name: "NOT",
operandType: "Logic Switches",
hasOperand: [true, false],
output: "boolean"
},
13: {
name: "STICKY",
name: "Sticky",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
14: {
name: "ADD",
name: "Basic: Add",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
15: {
name: "SUB",
name: "Basic: Subtract",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
16: {
name: "MUL",
name: "Basic: Multiply",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
17: {
name: "DIV",
name: "Basic: Divide",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
40: {
name: "MOD",
name: "Modulo",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
18: {
name: "GVAR SET",
name: "Set GVAR",
operandType: "Variables",
hasOperand: [true, true],
output: "none"
},
19: {
name: "GVAR INC",
name: "Increase GVAR",
operandType: "Variables",
hasOperand: [true, true],
output: "none"
},
20: {
name: "GVAR DEC",
name: "Decrease GVAR",
operandType: "Variables",
hasOperand: [true, true],
output: "none"
},
21: {
name: "IO PORT SET",
name: "Set IO Port",
operandType: "Set Flight Parameter",
hasOperand: [true, true],
output: "none"
},
22: {
name: "OVERRIDE ARMING SAFETY",
name: "Override Arming Safety",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
23: {
name: "OVERRIDE THROTTLE SCALE",
name: "Override Throttle Scale",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
29: {
name: "OVERRIDE THROTTLE",
name: "Override Throttle",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
24: {
name: "SWAP ROLL & YAW",
name: "Swap Roll & Yaw",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
25: {
name: "SET VTX POWER LEVEL",
name: "Set VTx Power Level",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
30: {
name: "SET VTX BAND",
name: "Set VTx Band",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
31: {
name: "SET VTX CHANNEL",
name: "Set VTx Channel",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
26: {
name: "INVERT ROLL",
name: "Invert Roll",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
27: {
name: "INVERT PITCH",
name: "Invert Pitch",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
28: {
name: "INVERT YAW",
name: "Invert Yaw",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
32: {
name: "SET OSD LAYOUT",
name: "Set OSD Layout",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
33: {
name: "SIN",
name: "Trigonometry: Sine",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
34: {
name: "COS",
name: "Trigonometry: Cosine",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
35: {
name: "TAN",
name: "Trigonometry: Tangent",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
36: {
name: "MAP INPUT",
name: "Map Input",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
37: {
name: "MAP OUTPUT",
name: "Map Output",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
38: {
name: "RC CHANNEL OVERRIDE",
name: "Override RC Channel",
operandType: "Set Flight Parameter",
hasOperand: [true, true],
output: "boolean"
},
41: {
name: "LOITER RADIUS OVERRIDE",
name: "Override Loiter Radius",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
42: {
name: "SET PROFILE",
name: "Set Profile",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
43: {
name: "MIN",
name: "Use Lowest Value",
operandType: "Comparison",
hasOperand: [true, true],
output: "raw"
},
44: {
name: "MAX",
name: "Use Highest Value",
operandType: "Comparison",
hasOperand: [true, true],
output: "raw"
},
@ -1324,6 +1210,7 @@ var FC = {
34: "GPS Valid Fix",
35: "Loiter Radius [cm]",
36: "Active Profile",
37: "Battery cells",
}
},
3: {
@ -1363,5 +1250,162 @@ var FC = {
default: 0
}
}
},
getBatteryProfileParameters: function () {
return [
'bat_cells',
'vbat_cell_detect_voltage',
'vbat_max_cell_voltage',
'vbat_min_cell_voltage',
'vbat_warning_cell_voltage',
'battery_capacity',
'battery_capacity_warning',
'battery_capacity_critical',
'battery_capacity_unit',
'controlrate_profile',
'throttle_scale',
'throttle_idle',
'turtle_mode_power_factor',
'failsafe_throttle',
'fw_min_throttle_down_pitch',
'nav_mc_hover_thr',
'nav_fw_cruise_thr',
'nav_fw_min_thr',
'nav_fw_max_thr',
'nav_fw_pitch2thr',
'nav_fw_launch_thr',
'nav_fw_launch_idle_thr',
'limit_cont_current',
'limit_burst_current',
'limit_burst_current_time',
'limit_burst_current_falldown_time',
'limit_cont_power',
'limit_burst_power',
'limit_burst_power_time',
'limit_burst_power_falldown_time'
];
},
isBatteryProfileParameter: function(paramName) {
return ($.inArray(paramName,this.getBatteryProfileParameters()) != -1);
},
getControlProfileParameters: function () {
return [
'mc_p_pitch',
'mc_i_pitch',
'mc_d_pitch',
'mc_cd_pitch',
'mc_p_roll',
'mc_i_roll',
'mc_d_roll',
'mc_cd_roll',
'mc_p_yaw',
'mc_i_yaw',
'mc_d_yaw',
'mc_cd_yaw',
'mc_p_level',
'mc_i_level',
'mc_d_level',
'fw_p_pitch',
'fw_i_pitch',
'fw_d_pitch',
'fw_ff_pitch',
'fw_p_roll',
'fw_i_roll',
'fw_d_roll',
'fw_ff_roll',
'fw_p_yaw',
'fw_i_yaw',
'fw_d_yaw',
'fw_ff_yaw',
'fw_p_level',
'fw_i_level',
'fw_d_level',
'max_angle_inclination_rll',
'max_angle_inclination_pit',
'dterm_lpf_hz',
'dterm_lpf_type',
'dterm_lpf2_hz',
'dterm_lpf2_type',
'yaw_lpf_hz',
'fw_iterm_throw_limit',
'fw_loiter_direction',
'fw_reference_airspeed',
'fw_turn_assist_yaw_gain',
'fw_turn_assist_pitch_gain',
'fw_iterm_limit_stick_position',
'fw_yaw_iterm_freeze_bank_angle',
'pidsum_limit',
'pidsum_limit_yaw',
'iterm_windup',
'rate_accel_limit_roll_pitch',
'rate_accel_limit_yaw',
'heading_hold_rate_limit',
'nav_mc_pos_z_p',
'nav_mc_vel_z_p',
'nav_mc_vel_z_i',
'nav_mc_vel_z_d',
'nav_mc_pos_xy_p',
'nav_mc_vel_xy_p',
'nav_mc_vel_xy_i',
'nav_mc_vel_xy_d',
'nav_mc_vel_xy_ff',
'nav_mc_heading_p',
'nav_mc_vel_xy_dterm_lpf_hz',
'nav_mc_vel_xy_dterm_attenuation',
'nav_mc_vel_xy_dterm_attenuation_start',
'nav_mc_vel_xy_dterm_attenuation_end',
'nav_fw_pos_z_p',
'nav_fw_pos_z_i',
'nav_fw_pos_z_d',
'nav_fw_pos_xy_p',
'nav_fw_pos_xy_i',
'nav_fw_pos_xy_d',
'nav_fw_heading_p',
'nav_fw_pos_hdg_p',
'nav_fw_pos_hdg_i',
'nav_fw_pos_hdg_d',
'nav_fw_pos_hdg_pidsum_limit',
'mc_iterm_relax',
'mc_iterm_relax_cutoff',
'd_boost_min',
'd_boost_max',
'd_boost_max_at_acceleration',
'd_boost_gyro_delta_lpf_hz',
'antigravity_gain',
'antigravity_accelerator',
'antigravity_cutoff_lpf_hz',
'pid_type',
'mc_cd_lpf_hz',
'fw_level_pitch_trim',
'smith_predictor_strength',
'smith_predictor_delay',
'smith_predictor_lpf_hz',
'fw_level_pitch_gain',
'thr_mid',
'thr_expo',
'tpa_rate',
'tpa_breakpoint',
'fw_tpa_time_constant',
'rc_expo',
'rc_yaw_expo',
'roll_rate',
'pitch_rate',
'yaw_rate',
'manual_rc_expo',
'manual_rc_yaw_expo',
'manual_roll_rate',
'manual_pitch_rate',
'manual_yaw_rate',
'fpv_mix_degrees',
'rate_dynamics_center_sensitivity',
'rate_dynamics_end_sensitivity',
'rate_dynamics_center_correction',
'rate_dynamics_end_correction',
'rate_dynamics_center_weight',
'rate_dynamics_end_weight'
];
},
isControlProfileParameter: function(paramName) {
return ($.inArray(paramName, this.getControlProfileParameters()) != -1);
}
};

View file

@ -1,4 +1,4 @@
/*global mspHelper,BF_CONFIG*/
/*global mspHelper,FEATURES,bit_clear,bit_set*/
'use strict';
var helper = helper || {};
@ -67,20 +67,20 @@ helper.features = (function() {
publicScope.execute = function(callback) {
exitPoint = callback;
mspHelper.loadBfConfig(privateScope.setBits);
mspHelper.loadFeatures(privateScope.setBits);
};
privateScope.setBits = function () {
for (const bit of toSet) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, bit);
FEATURES = bit_set(FEATURES, bit);
}
for (const bit of toUnset) {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, bit);
FEATURES = bit_clear(FEATURES, bit);
}
mspHelper.saveBfConfig(exitPoint);
mspHelper.saveFeatures(exitPoint);
}
return publicScope;

View file

@ -18,7 +18,6 @@ var GUI_control = function () {
];
this.defaultAllowedTabsWhenConnected = [
'failsafe',
'transponder',
'adjustments',
'auxiliary',
'cli',

View file

@ -256,16 +256,55 @@ let LogicCondition = function (enabled, activatorId, operation, operandAType, op
$row.find('.logic_cell__operation').html("<select class='logic_element__operation' ></select>");
let $t = $row.find('.logic_element__operation');
for (let k in FC.getLogicOperators()) {
if (FC.getLogicOperators().hasOwnProperty(k)) {
let o = FC.getLogicOperators()[k];
if (self.getOperation() == parseInt(k, 10)) {
$t.append('<option value="' + k + '" selected>' + o.name + '</option>');
} else {
$t.append('<option value="' + k + '">' + o.name + '</option>');
}
let lcOperators = [];
for (let lcID in FC.getLogicOperators()) {
if (FC.getLogicOperators().hasOwnProperty(lcID)) {
let op = FC.getLogicOperators()[lcID];
lcOperators[parseInt(lcID, 10)] = {
id: parseInt(lcID, 10),
name: op.name,
operandType: op.operandType,
hasOperand: op.hasOperand,
output: op.output
};
}
}
lcOperators.sort((a, b) => {
let lcAT = a.operandType.toLowerCase(),
lcBT = b.operandType.toLowerCase(),
lcAN = a.name.toLowerCase(),
lcBN = b.name.toLowerCase();
if (lcAT == lcBT) {
return (lcAN < lcBN) ? -1 : (lcAN > lcBN) ? 1 : 0;
} else {
return (lcAT < lcBT) ? -1 : 1;
}
});
let section = "";
lcOperators.forEach( val => {
if (section != val.operandType) {
if (section != "") {
$t.append('</optgroup>');
}
section = val.operandType;
$t.append('<optgroup label="** ' + val.operandType + ' **">');
}
if (self.getOperation() == val.id) {
$t.append('<option value="' + val.id + '" selected>' + val.name + '</option>');
} else {
$t.append('<option value="' + val.id + '">' + val.name + '</option>');
}
});
$t.append('</optgroup>');
$t.change(self.onOperatorChange);
self.renderOperand(0);

View file

@ -44,6 +44,7 @@ const
// generate mixer
const mixerList = [
// ** Multirotor
{
id: 1,
name: 'Tricopter',
@ -60,7 +61,7 @@ const mixerList = [
servoMixer: [
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
}, // 1
}, // 1
{
id: 3,
name: 'Quad X',
@ -76,7 +77,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -1.0, -1.0), // FRONT_L
],
servoMixer: []
}, // 3
}, // 3
{
id: 2,
name: 'Quad +',
@ -92,7 +93,7 @@ const mixerList = [
new MotorMixRule(1.0, 0.0, -1.0, -1.0), // FRONT
],
servoMixer: []
}, // 2
}, // 2
{
id: 4,
name: 'Bicopter',
@ -103,18 +104,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 4
{
id: 5,
name: 'Gimbal',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 5
}, // 4
{
id: 6,
name: 'Y6',
@ -132,7 +122,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -0.666667, 1.0), // UNDER_LEFT
],
servoMixer: []
}, // 6
}, // 6
{
id: 7,
name: 'Hex +',
@ -150,45 +140,7 @@ const mixerList = [
new MotorMixRule(1.0, 0.0, 1.0, -1.0), // REAR
],
servoMixer: []
}, // 7
{
id: 8,
name: 'Flying Wing',
model: 'flying_wing',
image: 'flying_wing',
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 8
{
id: 27,
name: 'Flying Wing with differential thrust',
model: 'flying_wing',
image: 'flying_wing',
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 27
}, // 7
{
id: 9,
name: 'Y4',
@ -204,7 +156,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -1.0, 0.0), // FRONT_L CW
],
servoMixer: []
}, // 9
}, // 9
{
id: 10,
name: 'Hex X',
@ -222,7 +174,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, 0.0, 1.0), // LEFT
],
servoMixer: []
}, // 10
}, // 10
{
id: 11,
name: 'Octo X8',
@ -242,7 +194,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -1.0, 1.0), // UNDER_FRONT_L
],
servoMixer: []
}, // 11
}, // 11
{
id: 12,
name: 'Octo Flat +',
@ -262,7 +214,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, 0.0, -1.0), // LEFT
],
servoMixer: []
}, // 12
}, // 12
{
id: 13,
name: 'Octo Flat X',
@ -282,51 +234,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, 0.414178, -1.0), // MIDREAR_L
],
servoMixer: []
}, // 13
{
id: 14,
name: 'Airplane',
model: 'twin_plane',
image: 'airplane',
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
hasFlaps: true,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
}, // 14
{
id: 15,
name: 'Heli 120',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 15
{
id: 16,
name: 'Heli 90',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 16
}, // 13
{
id: 17,
name: 'V-tail Quad',
@ -360,18 +268,7 @@ const mixerList = [
new MotorMixRule(1.0, 0.0, 0.0, 0.0), // LEFT
],
servoMixer: []
}, // 18
{
id: 19,
name: 'PPM to SERVO',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 19
}, // 18
{
id: 20,
name: 'Dualcopter',
@ -382,7 +279,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 20
}, // 20
{
id: 21,
name: 'Singlecopter',
@ -393,7 +290,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 21
}, // 21
{
id: 22,
name: 'A-tail Quad',
@ -420,18 +317,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 23
{
id: 24,
name: 'Custom Airplane',
model: 'twin_plane',
image: 'airplane',
enabled: false,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [],
servoMixer: []
}, // 24
}, // 23
{
id: 25,
name: 'Custom Tricopter',
@ -442,12 +328,96 @@ const mixerList = [
platform: PLATFORM_TRICOPTER,
motorMixer: [],
servoMixer: []
}, // 25
}, // 25
// ** Fixed Wing **
{
id: 8,
name: 'Flying Wing',
model: 'flying_wing',
image: 'flying_wing',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 123, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 123, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:93, left:71, colour: "#000000"},
],
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 8
{
id: 27,
name: 'Flying Wing with differential thrust',
model: 'flying_wing',
image: 'flying_wing',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 123, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 123, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:93, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 27
{
id: 14,
name: 'Airplane',
model: 'twin_plane',
image: 'airplane',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_YAW, top: 126, left: 52, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
hasFlaps: true,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
}, // 14
{
id: 26,
name: 'Airplane with differential thrust',
model: 'twin_plane',
image: 'airplane',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_YAW, top: 126, left: 52, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -464,12 +434,19 @@ const mixerList = [
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
},
}, // 26
{
id: 28,
name: 'Airplane V-tail (individual aileron servos)',
name: 'Airplane V-tail',
model: 'vtail_plane',
image: 'airplane_vtail',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 20, colour: "#ff7f00"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 132, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -487,12 +464,49 @@ const mixerList = [
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
]
},
}, // 28
{
id: 34,
name: 'Airplane V-tail with differential thrust',
model: 'vtail_plane',
image: 'airplane_vtail',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 20, colour: "#ff7f00"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 132, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
hasFlaps: true,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
new MotorMixRule(1.0, 0.0, 0.0, -0.3)
],
servoMixer: [
new ServoMixRule(1, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(1, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(2, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(3, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
]
}, // 34
{
id: 29,
name: 'Airplane V-tail (single aileron servo)',
model: 'vtail_single_servo_plane',
image: 'airplane_vtail_single',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff7f00"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 20, colour: "#ff0000"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 132, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -506,12 +520,18 @@ const mixerList = [
new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
]
},
}, //29
{
id: 30,
name: 'Airplane without rudder',
model: 'rudderless_plane',
image: 'airplane_norudder',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -526,7 +546,51 @@ const mixerList = [
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0),*/
]
},
}, // 30
{
id: 24,
name: 'Custom Airplane',
model: 'twin_plane',
image: 'airplane',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_YAW, top: 126, left: 52, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: false,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [],
servoMixer: []
}, // 24
// ** Helicopter **
{
id: 15,
name: 'Heli 120',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 15
{
id: 16,
name: 'Heli 90',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 16
// ** Other platforms **
{
id: 31,
name: 'Rover',
@ -556,8 +620,8 @@ const mixerList = [
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
}
,
},
// ** Misc **
{
id: 33,
name: 'Other',
@ -572,7 +636,29 @@ const mixerList = [
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
}
},
{
id: 5,
name: 'Gimbal',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 5
{
id: 19,
name: 'PPM to SERVO',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 19
];
const platformList = [

View file

@ -7,9 +7,9 @@ var MotorMixRule = function (throttle, roll, pitch, yaw) {
self.fromMsp = function (mspThrottle, mspRoll, mspPitch, mspYaw) {
throttle = mspThrottle / 1000;
roll = (mspRoll / 1000) - 2;
pitch = (mspPitch / 1000) - 2;
yaw = (mspYaw / 1000) - 2;
roll = Math.round(((mspRoll / 1000) - 2) * 1000) / 1000;
pitch = Math.round(((mspPitch / 1000) - 2) * 1000) / 1000;
yaw = Math.round(((mspYaw / 1000) - 2) * 1000) / 1000;
};
self.isUsed = function () {

View file

@ -57,7 +57,7 @@ var MSP = {
CHECKSUM_V1: 16,
CHECKSUM_V2: 17,
},
protocolVersion: 1, // this.constants.PROTOCOL_V1
protocolVersion: 2, // this.constants.PROTOCOL_V2
state: 0, // this.decoder_states.IDLE
message_direction: 1,
code: 0,
@ -72,7 +72,7 @@ var MSP = {
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
last_received_timestamp: null,

View file

@ -33,6 +33,12 @@ var MSPCodes = {
MSP_SET_CHANNEL_FORWARDING: 33,
MSP_MODE_RANGES: 34,
MSP_SET_MODE_RANGE: 35,
MSP_FEATURE: 36,
MSP_SET_FEATURE: 37,
MSP_BOARD_ALIGNMENT: 38,
MSP_SET_BOARD_ALIGNMENT: 39,
MSP_CURRENT_METER_CONFIG: 40,
MSP_SET_CURRENT_METER_CONFIG: 41,
MSP_RX_CONFIG: 44,
MSP_SET_RX_CONFIG: 45,
MSP_LED_COLORS: 46,
@ -44,8 +50,6 @@ var MSPCodes = {
MSP_CF_SERIAL_CONFIG: 54,
MSP_SET_CF_SERIAL_CONFIG: 55,
MSP_SONAR: 58,
MSP_PID_CONTROLLER: 59,
MSP_SET_PID_CONTROLLER: 60,
MSP_ARMING_CONFIG: 61,
MSP_SET_ARMING_CONFIG: 62,
MSP_DATAFLASH_SUMMARY: 70,
@ -60,8 +64,6 @@ var MSPCodes = {
MSP_SDCARD_SUMMARY: 79,
MSP_BLACKBOX_CONFIG: 80,
MSP_SET_BLACKBOX_CONFIG: 81,
MSP_TRANSPONDER_CONFIG: 82,
MSP_SET_TRANSPONDER_CONFIG: 83,
MSP_OSD_CONFIG: 84,
MSP_SET_OSD_CONFIG: 85,
MSP_OSD_CHAR_READ: 86,
@ -103,7 +105,7 @@ var MSPCodes = {
MSP_RC_DEADBAND: 125,
MSP_SENSOR_ALIGNMENT: 126,
MSP_LED_STRIP_MODECOLOR:127,
MSP_STATUS_EX: 150,
MSP_STATUS_EX: 150, // Deprecated, do not use.
MSP_SENSOR_STATUS: 151,
MSP_SET_RAW_RC: 200,
@ -149,10 +151,10 @@ var MSPCodes = {
// Additional private MSP for baseflight configurator (yes thats us \o/)
MSP_RX_MAP: 64, // get channel map (also returns number of channels total)
MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
MSP_BF_CONFIG: 66, // Depreciated
MSP_SET_BF_CONFIG: 67, // Depreciated
MSP_SET_REBOOT: 68, // reboot settings
MSP_BF_BUILD_INFO: 69, // build date as well as some space for future expansion
MSP_BF_BUILD_INFO: 69, // Depreciated
// INAV specific codes
MSPV2_SETTING: 0x1003,

View file

@ -68,36 +68,6 @@ var mspHelper = (function (gui) {
colorCount,
color;
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
case MSPCodes.MSP_IDENT:
//FIXME remove this frame when proven not needed
console.log('Using deprecated msp command: MSP_IDENT');
// Deprecated
CONFIG.version = parseFloat((data.getUint8(0) / 100).toFixed(2));
CONFIG.multiType = data.getUint8(1);
CONFIG.msp_version = data.getUint8(2);
CONFIG.capability = data.getUint32(3, true);
break;
case MSPCodes.MSP_STATUS:
console.log('Using deprecated msp command: MSP_STATUS');
CONFIG.cycleTime = data.getUint16(0, true);
CONFIG.i2cError = data.getUint16(2, true);
CONFIG.activeSensors = data.getUint16(4, true);
CONFIG.mode = data.getUint32(6, true);
CONFIG.profile = data.getUint8(10);
gui.updateProfileChange();
gui.updateStatusBar();
break;
case MSPCodes.MSP_STATUS_EX:
CONFIG.cycleTime = data.getUint16(0, true);
CONFIG.i2cError = data.getUint16(2, true);
CONFIG.activeSensors = data.getUint16(4, true);
CONFIG.profile = data.getUint8(10);
CONFIG.cpuload = data.getUint16(11, true);
CONFIG.armingFlags = data.getUint16(13, true);
gui.updateStatusBar();
gui.updateProfileChange();
break;
case MSPCodes.MSPV2_INAV_STATUS:
CONFIG.cycleTime = data.getUint16(offset, true);
offset += 2;
@ -134,12 +104,7 @@ var mspHelper = (function (gui) {
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
SENSOR_STATUS.imu2HwStatus = data.getUint8(9);
} else {
SENSOR_STATUS.imu2HwStatus = 0;
}
SENSOR_STATUS.imu2HwStatus = data.getUint8(9);
sensor_status_ex(SENSOR_STATUS);
break;
@ -293,14 +258,6 @@ var mspHelper = (function (gui) {
RC_tuning.manual_pitch_rate = data.getUint8(offset++);
RC_tuning.manual_yaw_rate = data.getUint8(offset++);
break;
case MSPCodes.MSP_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 3); i++, needle += 3) {
PIDs[i][0] = data.getUint8(needle);
PIDs[i][1] = data.getUint8(needle + 1);
PIDs[i][2] = data.getUint8(needle + 2);
}
break;
case MSPCodes.MSP2_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
@ -640,9 +597,6 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_SET_RAW_GPS:
break;
case MSPCodes.MSP_SET_PID:
console.log('PID settings saved');
break;
case MSPCodes.MSP2_SET_PID:
console.log('PID settings saved');
break;
@ -734,19 +688,36 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_SET_RX_MAP:
console.log('RCMAP saved');
break;
case MSPCodes.MSP_BF_CONFIG:
BF_CONFIG.mixerConfiguration = data.getUint8(0);
BF_CONFIG.features = data.getUint32(1, true);
BF_CONFIG.serialrx_type = data.getUint8(5);
BF_CONFIG.board_align_roll = data.getInt16(6, true); // -180 - 360
BF_CONFIG.board_align_pitch = data.getInt16(8, true); // -180 - 360
BF_CONFIG.board_align_yaw = data.getInt16(10, true); // -180 - 360
BF_CONFIG.currentscale = data.getInt16(12, true);
BF_CONFIG.currentoffset = data.getInt16(14, true);
case MSPCodes.MSP_BOARD_ALIGNMENT:
BOARD_ALIGNMENT.roll = data.getInt16(0, true); // -180 - 360
BOARD_ALIGNMENT.pitch = data.getInt16(2, true); // -180 - 360
BOARD_ALIGNMENT.yaw = data.getInt16(4, true); // -180 - 360
break;
case MSPCodes.MSP_SET_BF_CONFIG:
console.log('BF_CONFIG saved');
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
console.log('MSP_SET_BOARD_ALIGNMENT saved');
break;
case MSPCodes.MSP_CURRENT_METER_CONFIG:
CURRENT_METER_CONFIG.scale = data.getInt16(0, true);
CURRENT_METER_CONFIG.offset = data.getInt16(2, true);
CURRENT_METER_CONFIG.type = data.getUint8(4);
CURRENT_METER_CONFIG.capacity = data.getInt16(5, true);
break;
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
console.log('MSP_SET_CURRENT_METER_CONFIG saved');
break;
case MSPCodes.MSP_FEATURE:
FEATURES = data.getUint32(0, true);
break;
case MSPCodes.MSP_SET_FEATURE:
console.log('MSP_SET_FEATURE saved');
break;
case MSPCodes.MSP_SET_REBOOT:
console.log('Reboot request accepted');
break;
@ -800,28 +771,6 @@ var mspHelper = (function (gui) {
console.log('Channel forwarding saved');
break;
case MSPCodes.MSP_CF_SERIAL_CONFIG:
SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 2 + 4;
var serialPortCount = data.byteLength / bytesPerPort;
for (i = 0; i < serialPortCount; i++) {
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
var serialPort = {
identifier: data.getUint8(offset),
functions: mspHelper.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, true)),
msp_baudrate: BAUD_RATES[data.getUint8(offset + 3)],
sensors_baudrate: BAUD_RATES[data.getUint8(offset + 4)],
telemetry_baudrate: BAUD_RATES[data.getUint8(offset + 5)],
blackbox_baudrate: BAUD_RATES[data.getUint8(offset + 6)]
};
offset += bytesPerPort;
SERIAL_CONFIG.ports.push(serialPort);
}
break;
case MSPCodes.MSP2_CF_SERIAL_CONFIG:
SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 4 + 4;
@ -844,7 +793,6 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
console.log('Serial config saved');
break;
@ -1154,17 +1102,6 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_SET_BLACKBOX_CONFIG:
console.log("Blackbox config saved");
break;
case MSPCodes.MSP_TRANSPONDER_CONFIG:
TRANSPONDER.supported = (data.getUint8(offset++) & 1) != 0;
TRANSPONDER.data = [];
var bytesRemaining = data.byteLength - offset;
for (i = 0; i < bytesRemaining; i++) {
TRANSPONDER.data.push(data.getUint8(offset++));
}
break;
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
console.log("Transponder config saved");
break;
case MSPCodes.MSP_VTX_CONFIG:
VTX_CONFIG.device_type = data.getUint8(offset++);
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
@ -1300,11 +1237,9 @@ var mspHelper = (function (gui) {
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
CALIBRATION_DATA.magGain.Z = data.getInt16(25, true);
}
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
CALIBRATION_DATA.magGain.Z = data.getInt16(25, true);
break;
@ -1494,6 +1429,7 @@ var mspHelper = (function (gui) {
BLACKBOX.blackboxDevice = data.getUint8(1);
BLACKBOX.blackboxRateNum = data.getUint16(2);
BLACKBOX.blackboxRateDenom = data.getUint16(4);
BLACKBOX.blackboxIncludeFlags = data.getUint32(6,true);
break;
case MSPCodes.MSP2_SET_BLACKBOX_CONFIG:
console.log("Blackbox config saved");
@ -1546,7 +1482,7 @@ var mspHelper = (function (gui) {
// fire callback
if (callback) {
callback({'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected});
callback({ 'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected });
}
break;
}
@ -1559,24 +1495,33 @@ var mspHelper = (function (gui) {
i;
switch (code) {
case MSPCodes.MSP_SET_BF_CONFIG:
buffer.push(BF_CONFIG.mixerConfiguration);
buffer.push(specificByte(BF_CONFIG.features, 0));
buffer.push(specificByte(BF_CONFIG.features, 1));
buffer.push(specificByte(BF_CONFIG.features, 2));
buffer.push(specificByte(BF_CONFIG.features, 3));
buffer.push(BF_CONFIG.serialrx_type);
buffer.push(specificByte(BF_CONFIG.board_align_roll, 0));
buffer.push(specificByte(BF_CONFIG.board_align_roll, 1));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 0));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 1));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 0));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 1));
buffer.push(lowByte(BF_CONFIG.currentscale));
buffer.push(highByte(BF_CONFIG.currentscale));
buffer.push(lowByte(BF_CONFIG.currentoffset));
buffer.push(highByte(BF_CONFIG.currentoffset));
case MSPCodes.MSP_SET_FEATURE:
buffer.push(specificByte(FEATURES, 0));
buffer.push(specificByte(FEATURES, 1));
buffer.push(specificByte(FEATURES, 2));
buffer.push(specificByte(FEATURES, 3));
break;
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 1));
buffer.push(specificByte(BOARD_ALIGNMENT.pitch, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.pitch, 1));
buffer.push(specificByte(BOARD_ALIGNMENT.yaw, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.yaw, 1));
break;
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
buffer.push(specificByte(CURRENT_METER_CONFIG.scale, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.scale, 1));
buffer.push(specificByte(CURRENT_METER_CONFIG.offset, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.offset, 1));
buffer.push(CURRENT_METER_CONFIG.type);
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 1));
break;
case MSPCodes.MSP_SET_VTX_CONFIG:
if (VTX_CONFIG.band > 0) {
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
@ -1589,13 +1534,6 @@ var mspHelper = (function (gui) {
buffer.push(0);
buffer.push(VTX_CONFIG.low_power_disarm);
break;
case MSPCodes.MSP_SET_PID:
for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
buffer.push(parseInt(PIDs[i][1]));
buffer.push(parseInt(PIDs[i][2]));
}
break;
case MSPCodes.MSP2_SET_PID:
for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
@ -1796,12 +1734,6 @@ var mspHelper = (function (gui) {
buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
break;
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
for (i = 0; i < TRANSPONDER.data.length; i++) {
buffer.push(TRANSPONDER.data[i]);
}
break;
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
for (i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;
@ -1812,24 +1744,6 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
buffer.push(serialPort.identifier);
var functionMask = mspHelper.SERIAL_PORT_FUNCTIONSToMask(serialPort.functions);
buffer.push(specificByte(functionMask, 0));
buffer.push(specificByte(functionMask, 1));
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.blackbox_baudrate));
}
break;
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
@ -1967,16 +1881,14 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
buffer.push(highByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
buffer.push(lowByte(CALIBRATION_DATA.magGain.X));
buffer.push(highByte(CALIBRATION_DATA.magGain.X));
buffer.push(lowByte(CALIBRATION_DATA.magGain.X));
buffer.push(highByte(CALIBRATION_DATA.magGain.X));
buffer.push(lowByte(CALIBRATION_DATA.magGain.Y));
buffer.push(highByte(CALIBRATION_DATA.magGain.Y));
buffer.push(lowByte(CALIBRATION_DATA.magGain.Y));
buffer.push(highByte(CALIBRATION_DATA.magGain.Y));
buffer.push(lowByte(CALIBRATION_DATA.magGain.Z));
buffer.push(highByte(CALIBRATION_DATA.magGain.Z));
}
buffer.push(lowByte(CALIBRATION_DATA.magGain.Z));
buffer.push(highByte(CALIBRATION_DATA.magGain.Z));
break;
@ -2129,14 +2041,11 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_WP_MISSION_SAVE:
// buffer.push(0);
console.log(buffer);
buffer.push(0);
break;
case MSPCodes.MSP_WP_MISSION_LOAD:
// buffer.push(0);
console.log(buffer);
case MSPCodes.MSP_WP_MISSION_LOAD:
buffer.push(0);
break;
case MSPCodes.MSP2_INAV_SET_MIXER:
@ -2147,6 +2056,8 @@ var mspHelper = (function (gui) {
buffer.push(MIXER_CONFIG.hasFlaps);
buffer.push(lowByte(MIXER_CONFIG.appliedMixerPreset));
buffer.push(highByte(MIXER_CONFIG.appliedMixerPreset));
buffer.push(0); //Filler byte to match expect payload length
buffer.push(0); //Filler byte to match expect payload length
break;
case MSPCodes.MSP2_INAV_SET_MC_BRAKING:
@ -2193,17 +2104,18 @@ var mspHelper = (function (gui) {
};
self.sendBlackboxConfiguration = function (onDataCallback) {
var buffer = [];
var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
buffer.push(BLACKBOX.blackboxDevice & 0xFF);
var buffer = [];
var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
buffer.push(BLACKBOX.blackboxDevice & 0xFF);
messageId = MSPCodes.MSP2_SET_BLACKBOX_CONFIG;
buffer.push(lowByte(BLACKBOX.blackboxRateNum));
buffer.push(highByte(BLACKBOX.blackboxRateNum));
buffer.push(lowByte(BLACKBOX.blackboxRateDenom));
buffer.push(highByte(BLACKBOX.blackboxRateDenom));
buffer.push32(BLACKBOX.blackboxIncludeFlags);
//noinspection JSUnusedLocalSymbols
MSP.send_message(messageId, buffer, false, function (response) {
onDataCallback();
onDataCallback();
});
};
@ -2370,9 +2282,7 @@ var mspHelper = (function (gui) {
buffer.push(conditionIndex);
buffer.push(condition.getEnabled());
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
buffer.push(condition.getActivatorId());
}
buffer.push(condition.getActivatorId());
buffer.push(condition.getOperation());
buffer.push(condition.getOperandAType());
buffer.push(specificByte(condition.getOperandAValue(), 0));
@ -2665,7 +2575,7 @@ var mspHelper = (function (gui) {
/*
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
*/
@ -2752,22 +2662,10 @@ var mspHelper = (function (gui) {
* Basic sending methods used for chaining purposes
*/
/**
* @deprecated
* @param callback
*/
self.loadMspIdent = function (callback) {
MSP.send_message(MSPCodes.MSP_IDENT, false, false, callback);
};
self.loadINAVPidConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
};
self.loadLoopTime = function (callback) {
MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, callback);
};
self.loadAdvancedConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, callback);
};
@ -2796,12 +2694,16 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_PIDNAMES, false, false, callback);
};
self.loadStatus = function (callback) {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
self.loadFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, callback);
};
self.loadBfConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, callback);
self.loadBoardAlignment = function (callback) {
MSP.send_message(MSPCodes.MSP_BOARD_ALIGNMENT, false, false, callback);
};
self.loadCurrentMeterConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, callback);
};
self.queryFcStatus = function (callback) {
@ -2821,7 +2723,7 @@ var mspHelper = (function (gui) {
};
self.loadBatteryConfig = function (callback) {
MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
};
self.loadArmingConfig = function (callback) {
@ -2876,10 +2778,6 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_INAV_PID, mspHelper.crunch(MSPCodes.MSP_SET_INAV_PID), false, callback);
};
self.saveLooptimeConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, callback);
};
self.saveAdvancedConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, callback);
};
@ -2904,8 +2802,16 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback);
};
self.saveBfConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, callback);
self.saveFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_FEATURE, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE), false, callback);
};
self.saveCurrentMeterConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, callback);
};
self.saveBoardAlignment = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_BOARD_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_BOARD_ALIGNMENT), false, callback);
};
self.saveMisc = function (callback) {
@ -2981,7 +2887,7 @@ var mspHelper = (function (gui) {
};
self.saveFwConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
};
self.getMissionInfo = function (callback) {
@ -3033,7 +2939,7 @@ var mspHelper = (function (gui) {
function nextSafehome() {
safehomeId++;
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
if (safehomeId < SAFEHOMES.getMaxSafehomeCount() - 1) {
MSP.send_message(MSPCodes.MSP2_INAV_SAFEHOME, [safehomeId], false, nextSafehome);
}
else {
@ -3048,7 +2954,7 @@ var mspHelper = (function (gui) {
function nextSendSafehome() {
safehomeId++;
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
if (safehomeId < SAFEHOMES.getMaxSafehomeCount() - 1) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_SAFEHOME, SAFEHOMES.extractBuffer(safehomeId), false, nextSendSafehome);
}
else {
@ -3077,9 +2983,7 @@ var mspHelper = (function (gui) {
var setting = {};
// Discard setting name
if (semver.gte(CONFIG.apiVersion, "2.4.0")) {
result.data.readString();
}
result.data.readString();
// Discard PG ID
result.data.readU16();
@ -3107,7 +3011,7 @@ var mspHelper = (function (gui) {
for (var ii = setting.min; ii <= setting.max; ii++) {
values.push(result.data.readString());
}
setting.table = {values: values};
setting.table = { values: values };
}
SETTINGS[name] = setting;
return setting;
@ -3162,7 +3066,7 @@ var mspHelper = (function (gui) {
default:
throw "Unknown setting type " + setting.type;
}
return {setting: setting, value: value};
return { setting: setting, value: value };
});
});
};
@ -3251,8 +3155,8 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, callback);
};
self.getCraftName = function(callback) {
MSP.send_message(MSPCodes.MSP_NAME, false, false, function(resp) {
self.getCraftName = function (callback) {
MSP.send_message(MSPCodes.MSP_NAME, false, false, function (resp) {
var name = resp.data.readString();
if (callback) {
callback(name);
@ -3260,7 +3164,7 @@ var mspHelper = (function (gui) {
});
};
self.setCraftName = function(name, callback) {
self.setCraftName = function (name, callback) {
var data = [];
name = name || "";
for (var ii = 0; ii < name.length; ii++) {
@ -3281,26 +3185,26 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
};
self.saveVTXConfig = function(callback) {
self.saveVTXConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
};
self.loadBrakingConfig = function(callback) {
self.loadBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
}
self.saveBrakingConfig = function(callback) {
self.saveBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
};
self.loadParameterGroups = function(callback) {
self.loadParameterGroups = function (callback) {
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
var groups = [];
while (resp.data.offset < resp.data.byteLength) {
var id = resp.data.readU16();
var start = resp.data.readU16();
var end = resp.data.readU16();
groups.push({id: id, start: start, end: end});
groups.push({ id: id, start: start, end: end });
}
if (callback) {
callback(groups);
@ -3308,7 +3212,7 @@ var mspHelper = (function (gui) {
});
};
self.loadBrakingConfig = function(callback) {
self.loadBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
}
@ -3317,19 +3221,11 @@ var mspHelper = (function (gui) {
};
self.loadGlobalVariablesStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_GVAR_STATUS, false, false, callback);
} else {
callback();
}
MSP.send_message(MSPCodes.MSP2_INAV_GVAR_STATUS, false, false, callback);
};
self.loadProgrammingPidStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
} else {
callback();
}
MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
};
return self;

View file

@ -62,7 +62,7 @@ $(document).ready(function () {
} else {
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceReady'));
//noinspection JSValidateTypes
@ -130,44 +130,52 @@ $(document).ready(function () {
helper.interval.killAll(['global_data_refresh', 'msp-load-update']);
helper.mspBalancedInterval.flush();
GUI.tab_switch_cleanup();
GUI.tab_switch_in_progress = false;
CONFIGURATOR.connectionValid = false;
GUI.connected_to = false;
GUI.allowedTabs = GUI.defaultAllowedTabsWhenDisconnected.slice();
/*
* Flush
*/
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
helper.mspQueue.freeSoftLock();
serial.disconnect(onClosed);
MSP.disconnect_cleanup();
// Reset various UI elements
$('span.i2c-error').text(0);
$('span.cycle-time').text(0);
$('span.cpu-load').text('');
// unlock port select & baud
$port.prop('disabled', false);
$baud.prop('disabled', false);
// reset connect / disconnect button
$('div.connect_controls a.connect').removeClass('active');
$('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connect'));
// reset active sensor indicators
sensor_status(0);
if (wasConnected) {
// detach listeners and remove element data
$('#content').empty();
if (CONFIGURATOR.cliActive) {
GUI.tab_switch_cleanup(finishDisconnect);
} else {
GUI.tab_switch_cleanup();
finishDisconnect();
}
$('#tabs .tab_landing a').click();
function finishDisconnect() {
GUI.tab_switch_in_progress = false;
CONFIGURATOR.connectionValid = false;
GUI.connected_to = false;
GUI.allowedTabs = GUI.defaultAllowedTabsWhenDisconnected.slice();
/*
* Flush
*/
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
helper.mspQueue.freeSoftLock();
serial.disconnect(onClosed);
MSP.disconnect_cleanup();
// Reset various UI elements
$('span.i2c-error').text(0);
$('span.cycle-time').text(0);
$('span.cpu-load').text('');
// unlock port select & baud
$port.prop('disabled', false);
$baud.prop('disabled', false);
// reset connect / disconnect button
$('div.connect_controls a.connect').removeClass('active');
$('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connect'));
// reset active sensor indicators
sensor_status(0);
if (wasConnected) {
// detach listeners and remove element data
$('#content').empty();
}
$('#tabs .tab_landing a').click();
}
}
$(this).data("clicks", !clicks);
@ -228,6 +236,13 @@ function onInvalidFirmwareVersion()
}
function onOpen(openInfo) {
if (FC.restartRequired) {
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("illegalStateRestartRequired") + "</strong></span>");
$('div.connect_controls a').click(); // disconnect
return;
}
if (openInfo) {
// update connected_to
GUI.connected_to = GUI.connecting_to;
@ -260,7 +275,12 @@ function onOpen(openInfo) {
if (!CONFIGURATOR.connectionValid) {
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
$('div.connect_controls ').click(); // disconnect
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
helper.mspQueue.freeSoftLock();
serial.emptyOutputBuffer();
$('div.connect_controls a').click(); // disconnect
}
}, 10000);
@ -268,11 +288,15 @@ function onOpen(openInfo) {
// request configuration data. Start with MSPv1 and
// upgrade to MSPv2 if possible.
MSP.protocolVersion = MSP.constants.PROTOCOL_V1;
MSP.protocolVersion = MSP.constants.PROTOCOL_V2;
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
if (CONFIG.apiVersion && semver.gte(CONFIG.apiVersion, "2.0.0")) {
MSP.protocolVersion = MSP.constants.PROTOCOL_V2;
if (CONFIG.apiVersion === "0.0.0") {
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("illegalStateRestartRequired") + "</strong></span>");
FC.restartRequired = true;
return;
}
GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
MSP.send_message(MSPCodes.MSP_FC_VARIANT, false, false, function () {
@ -334,12 +358,8 @@ function onConnect() {
/*
* Init PIDs bank with a length that depends on the version
*/
let pidCount;
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
pidCount = 11;
} else {
pidCount = 10;
}
let pidCount = 11;
for (let i = 0; i < pidCount; i++) {
PIDs.push(new Array(4));
}
@ -438,7 +458,7 @@ function sensor_status_hash(hw_status)
hw_status.gpsHwStatus +
hw_status.rangeHwStatus +
hw_status.speedHwStatus +
hw_status.flowHwStatus +
hw_status.flowHwStatus +
hw_status.imu2HwStatus;
}

View file

@ -72,6 +72,21 @@ let ServoMixerRuleCollection = function () {
return false;
};
self.getServoMixRuleFromTarget = function(wantedTarget) {
let returnTarget = null;
for (let ruleIndex in data) {
if (data.hasOwnProperty(ruleIndex)) {
if (data[ruleIndex].getTarget() == wantedTarget) {
returnTarget = data[ruleIndex];
break;
}
}
}
return returnTarget;
}
self.getNumberOfConfiguredServos = function () {
let count = 0;
for (let i = 0; i < self.getServoCount(); i ++) {
@ -99,5 +114,20 @@ let ServoMixerRuleCollection = function () {
});
}
self.getNextUnusedIndex = function() {
let nextTarget = 0;
for (let ruleIndex in data) {
if (data.hasOwnProperty(ruleIndex)) {
let target = data[ruleIndex].getTarget();
if (target > nextTarget) {
nextTarget = target;
}
}
}
return nextTarget+1;
}
return self;
};

View file

@ -12,6 +12,16 @@ var Settings = (function () {
var settingName = input.data('setting');
var inputUnit = input.data('unit');
if (globalSettings.showProfileParameters) {
if (FC.isBatteryProfileParameter(settingName)) {
input.css("background-color","#fef2d5");
}
if (FC.isControlProfileParameter(settingName)) {
input.css("background-color","#d5ebfe");
}
}
return mspHelper.getSetting(settingName).then(function (s) {
// Check if the input declares a parent
// to be hidden in case of the setting not being available.
@ -28,6 +38,8 @@ var Settings = (function () {
}
parent.show();
input.prop('title', 'CLI: ' + input.data('setting'));
if (input.prop('tagName') == 'SELECT' || s.setting.table) {
if (input.attr('type') == 'checkbox') {
input.prop('checked', s.value > 0);
@ -63,20 +75,20 @@ var Settings = (function () {
} else {
input.attr('step', "0.01");
}
input.attr('min', s.setting.min);
input.attr('max', s.setting.max);
input.val(s.value.toFixed(2));
} else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
input.attr('type', 'number');
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
if (s.setting.min) {
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
input.attr('type', 'number');
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier)));
}
if (s.setting.max) {
if (typeof s.setting.max !== 'undefined' && s.setting.max !== null) {
input.attr('max', (s.setting.max / multiplier).toFixed(Math.log10(multiplier)));
}
}
@ -112,19 +124,19 @@ var Settings = (function () {
const getUnitDisplayTypeValue = () => {
// Try and match the values
switch (configUnitType) {
case UnitType.imperial:
return 0;
break;
case UnitType.metric:
return 1;
break;
case UnitType.OSD: // Match the OSD value on the UI
return globalSettings.osdUnits;
break;
case UnitType.imperial:
return 0; // Imperial OSD Value
break;
case UnitType.metric:
return 1; // Metric + MPH OSD Value
break;
case UnitType.none:
default:
// Something went wrong
return -1;
break;
}
}
@ -134,67 +146,237 @@ var Settings = (function () {
const oldValue = element.val();
//display names for the units
const unitDisplayDames = {
// Misc
'us' : "uS",
'cw' : 'cW',
'percent' : '%',
'cmss' : 'cm/s/s',
// Time
'msec' : 'ms',
'dsec' : 'ds',
'sec' : 's',
// Angles
'deg' : '&deg;',
'decideg' : 'deci&deg;',
'decideg-lrg' : 'deci&deg;', // Decidegrees, but always converted to degrees by default
// Rotational speed
'degps' : '&deg; per second',
'decadegps' : 'deca&deg; per second',
// Temperature
'decidegc' : 'deci&deg;C',
'degc' : '&deg;C',
'degf' : '&deg;F',
// Speed
'cms' : 'cm/s',
'v-cms' : 'cm/s',
'ms' : 'm/s',
'kmh' : 'Km/h',
'mph' : 'mph',
'hftmin' : 'x100 ft/min',
'fts' : 'ft/s',
'kt' : 'Kt',
// Distance
'cm' : 'cm',
'm' : 'm',
'km' : 'Km',
'm-lrg' : 'm', // Metres, but converted to larger units
'ft' : 'ft',
'mi' : 'mi',
'nm' : 'NM'
}
// Ensure we can do conversions
if (configUnitType === UnitType.none || uiUnitValue === -1 || !inputUnit || !oldValue || !element) {
if (!inputUnit || !oldValue || !element) {
return;
}
// Used to convert between a value and a value matching the int
// unit display value. Eg 1 = Metric
// units. We use the OSD unit values here for easy
const conversionTable = {
1: {
'cm': { multiplier: 100, unitName: 'm' },
'cms': { multiplier: 27.77777777777778, unitName: 'Km/h' }
//this is used to get the factor in which we multiply
//to get the correct conversion, the first index is the from
//unit and the second is the too unit
//unitConversionTable[toUnit][fromUnit] -> factor
const unitRatioTable = {
'cm' : {
'm' : 100,
'ft' : 30.48
},
2: {
'cm': { multiplier: 100, unitName: 'm' },
},
4: {
'cms': { multiplier: 51.44444444444457, unitName: 'Kt' }
'm' : {
'm' : 1,
'ft' : 0.3048
},
default: {
'cm': { multiplier: 30.48, unitName: 'ft' },
'cms': { multiplier: 44.704, unitName: 'mph' },
'ms': { multiplier: 1000, unitName: 'sec' }
'm-lrg' : {
'km' : 1000,
'mi' : 1609.344,
'nm' : 1852
},
}
'cms' : { // Horizontal speed
'kmh' : 27.77777777777778,
'kt': 51.44444444444457,
'mph' : 44.704,
'ms' : 100
},
'v-cms' : { // Vertical speed
'ms' : 100,
'hftmin' : 50.8,
'fts' : 30.48
},
'msec' : {
'sec' : 1000
},
'dsec' : {
'sec' : 10
},
'decideg' : {
'deg' : 10
},
'decideg-lrg' : {
'deg' : 10
},
'decadegps' : {
'degps' : 0.1
},
'decidegc' : {
'degc' : 10,
'degf' : 'FAHREN'
},
};
// Small closure to try and get the multiplier
// needed from the conversion table
const getUnitMultiplier = () => {
if(conversionTable[uiUnitValue] && conversionTable[uiUnitValue][inputUnit]) {
return conversionTable[uiUnitValue][inputUnit];
//this holds which units get converted in which unit systems
const conversionTable = {
0: { //imperial
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'mi',
'cms' : 'mph',
'v-cms' : 'fts',
'msec' : 'sec',
'dsec' : 'sec',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'decidegc' : 'degf',
},
1: { //metric
'cm': 'm',
'm' : 'm',
'm-lrg' : 'km',
'cms' : 'kmh',
'v-cms' : 'ms',
'msec' : 'sec',
'dsec' : 'sec',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'decidegc' : 'degc',
},
2: { //metric with MPH
'cm': 'm',
'm' : 'm',
'm-lrg' : 'km',
'cms' : 'mph',
'v-cms' : 'ms',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
3:{ //UK
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'mi',
'cms' : 'mph',
'v-cms' : 'fts',
'decadegps' : 'degpd',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
4: { //General aviation
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'nm',
'cms': 'kt',
'v-cms' : 'hftmin',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
default: { //show base units
'decadegps' : 'degps',
'decideg-lrg' : 'deg',
}
return conversionTable['default'][inputUnit];
};
//this returns the factor in which to multiply to convert a unit
const getUnitMultiplier = () => {
let uiUnits = (uiUnitValue != -1) ? uiUnitValue : 'default';
if (conversionTable[uiUnits]){
const fromUnits = conversionTable[uiUnits];
if (fromUnits[inputUnit]){
const multiplier = unitRatioTable[inputUnit][fromUnits[inputUnit]];
return {'multiplier':multiplier, 'unitName':fromUnits[inputUnit]};
}
}
return {multiplier:1, unitName:inputUnit};
}
// Get the default multi obj or the custom
const multiObj = getUnitMultiplier();
if(!multiObj) {
return;
}
const multiplier = multiObj.multiplier;
const unitName = multiObj.unitName;
// Update the step, min, and max; as we have the multiplier here.
if (element.attr('type') == 'number') {
element.attr('step', ((multiplier != 1) ? '0.01' : '1'));
element.attr('min', (element.attr('min') / multiplier).toFixed(2));
element.attr('max', (element.attr('max') / multiplier).toFixed(2));
let step = element.attr('step') || 1;
let decimalPlaces = 0;
step = step / multiplier;
if (step < 1) {
decimalPlaces = step.toString().length - step.toString().indexOf(".") - 1;
if (parseInt(step.toString().slice(-1)) > 1 ) {
decimalPlaces--;
}
step = 1 / Math.pow(10, decimalPlaces);
}
element.attr('step', step.toFixed(decimalPlaces));
if (multiplier != 'FAHREN') {
element.attr('min', (element.attr('min') / multiplier).toFixed(decimalPlaces));
element.attr('max', (element.attr('max') / multiplier).toFixed(decimalPlaces));
}
}
// Update the input with a new formatted unit
const convertedValue = Number((oldValue / multiplier).toFixed(2));
const newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
let newValue = "";
if (multiplier == 'FAHREN') {
element.attr('min', toFahrenheit(element.attr('min')).toFixed(2));
element.attr('max', toFahrenheit(element.attr('max')).toFixed(2));
newValue = toFahrenheit(oldValue).toFixed(2);
} else {
const convertedValue = Number((oldValue / multiplier).toFixed(2));
newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
}
element.val(newValue);
element.data('setting-multiplier', multiplier);
// Now wrap the input in a display that shows the unit
element.wrap(`<div data-unit="${unitName}" class="unit_wrapper unit"></div>`);
element.wrap(`<div data-unit="${unitDisplayDames[unitName]}" class="unit_wrapper unit"></div>`);
function toFahrenheit(decidegC) {
return (decidegC / 10) * 1.8 + 32;
};
}
self.saveInput = function(input) {
@ -215,8 +397,13 @@ var Settings = (function () {
} else if(setting.type == 'string') {
value = input.val();
} else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
value = parseFloat(input.val()) * multiplier;
var multiplier = input.data('setting-multiplier') || 1;
if (multiplier == 'FAHREN') {
value = Math.round(((parseFloat(input.val())-32) / 1.8) * 10);
} else {
multiplier = parseFloat(multiplier);
value = Math.round(parseFloat(input.val()) * multiplier);
}
}
return mspHelper.setSetting(settingName, value);
};

View file

@ -1,25 +0,0 @@
'use strict';
var helper = helper || {};
helper.task = (function () {
var publicScope = {},
privateScope = {};
privateScope.getStatusPullInterval = function () {
//TODO use serial connection speed to determine update interval
return 250;
};
publicScope.statusPullStart = function () {
helper.interval.add('status_pull', function () {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
});
}, privateScope.getStatusPullInterval(), true);
};
return publicScope;
})();

View file

@ -37,10 +37,14 @@ a.disabled {
}
/* Help-Icon */
.gui_box_titlebar .helpicon {
margin-right: 10px;
margin-top: 5px !important;
}
.helpicon {
float: right;
margin-top: 7px;
margin-right: 7px;
display: block;
height: 14px;
width: 14px;
@ -902,18 +906,6 @@ li.active .ic_flasher {
background-image: url("../images/icons/cf_icon_flasher_white.svg");
}
.ic_transponder {
background-image: url("../images/icons/cf_icon_transponder_grey.svg");
}
.ic_transponder:hover {
background-image: url("../images/icons/cf_icon_transponder_white.svg");
}
li.active .ic_transponder {
background-image: url("../images/icons/cf_icon_transponder_white.svg");
}
.ic_calibration {
background-image: url(../images/icons/cf_icon_cal_grey.svg);
}
@ -1974,7 +1966,6 @@ dialog {
.helpicon {
float: right;
margin-top: 5px;
margin-right: 7px;
height: 14px;
width: 14px;
transition: none;
@ -2233,11 +2224,21 @@ ol li {
position: relative;
}
.unit_wrapper input {
margin-right: 0 !important;
}
.unit_wrapper ~ label, select ~ label, input ~ label {
margin-left: 10px;
}
/* Position the unit to the right of the wrapper */
.unit_wrapper::after {
position: absolute;
top: 2px;
right: .7em;
/*top: 2px;*/
bottom: -2px;
height: 100%;
right: .5em;
transition: all .05s ease-in-out;
}
@ -2245,13 +2246,13 @@ ol li {
for arrow buttons will appear to the right of number inputs */
.unit_wrapper:hover::after,
.unit_wrapper:focus-within::after {
right: 1.3em;
right: 1.0em;
}
/* Handle Firefox (arrows always shown) */
@supports (-moz-appearance:none) {
.unit_wrapper::after {
right: 1.3em;
right: 1.0em;
}
}
@ -2259,3 +2260,19 @@ ol li {
.unit::after {
content: attr(data-unit) ;
}
.batteryProfileHighlight {
background-color: none;
}
.batteryProfileHighlightActive {
background-color: #fef2d5;
}
.controlProfileHighlight {
background-color:none;
}
.controlProfileHighlightActive {
background-color: #d5ebfe;
}

View file

@ -234,7 +234,6 @@
<li class="tab_osd">
<a href="#" data-i18n="tabOSD" class="tabicon ic_osd" title="OSD"></a>
</li>
<!--<li class="tab_transponder"><a href="#" data-i18n="tabTransponder" class="tabicon ic_transponder" title="Transponder"></a></li>-->
<li class="tab_led_strip">
<a href="#" data-i18n="tabLedStrip" class="tabicon ic_led" title="LED Strip"></a>
</li>

69
main.js
View file

@ -28,7 +28,8 @@ let globalSettings = {
mapProviderType: null,
mapApiKey: null,
proxyURL: null,
proxyLayer: null
proxyLayer: null,
showProfileParameters: null,
};
$(document).ready(function () {
@ -65,6 +66,14 @@ $(document).ready(function () {
}
globalSettings.proxyLayer = result.proxylayer;
});
chrome.storage.local.get('show_profile_parameters', function (result) {
if (typeof result.show_profile_parameters === 'undefined') {
result.show_profile_parameters = 1;
}
globalSettings.showProfileParameters = result.show_profile_parameters;
// Update CSS on to show highlighing or not
updateProfilesHighlightColours();
});
// Resets the OSD units used by the unit coversion when the FC is disconnected.
if (!CONFIGURATOR.connectionValid) {
@ -194,6 +203,9 @@ $(document).ready(function () {
function content_ready() {
GUI.tab_switch_in_progress = false;
// Update CSS on to show highlighing or not
updateProfilesHighlightColours();
}
switch (tab) {
@ -218,9 +230,6 @@ $(document).ready(function () {
case 'failsafe':
TABS.failsafe.initialize(content_ready);
break;
case 'transponder':
TABS.transponder.initialize(content_ready);
break;
case 'setup':
TABS.setup.initialize(content_ready);
break;
@ -330,12 +339,28 @@ $(document).ready(function () {
googleAnalyticsConfig.setTrackingPermitted(check);
});
$('div.show_profile_parameters input').change(function () {
globalSettings.showProfileParameters = $(this).is(':checked');
chrome.storage.local.set({
'show_profile_parameters': globalSettings.showProfileParameters
});
// Update CSS on select boxes
updateProfilesHighlightColours();
// Horrible way to reload the tab
const activeTab = $('#tabs li.active');
activeTab.removeClass('active');
activeTab.find('a').click();
});
$('#ui-unit-type').val(globalSettings.unitType);
$('#map-provider-type').val(globalSettings.mapProviderType);
$('#map-api-key').val(globalSettings.mapApiKey);
$('#proxyurl').val(globalSettings.proxyURL);
$('#proxylayer').val(globalSettings.proxyLayer);
$('#proxylayer').val(globalSettings.proxyLayer);
$('#showProfileParameters').prop('checked', globalSettings.showProfileParameters);
// Set the value of the unit type
// none, OSD, imperial, metric
$('#ui-unit-type').change(function () {
@ -511,7 +536,7 @@ $(document).ready(function () {
profile_e.change(function () {
var profile = parseInt($(this).val());
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [profile], false, function () {
GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1]));
GUI.log(chrome.i18n.getMessage('pidTuning_LoadedProfile', [profile + 1]));
updateActivatedTab();
});
});
@ -545,6 +570,36 @@ function get_osd_settings() {
});
}
function updateProfilesHighlightColours() {
if (globalSettings.showProfileParameters) {
$('.dropdown-dark #profilechange').addClass('showProfileParams');
$('.dropdown-dark #batteryprofilechange').addClass('showProfileParams');
$('.batteryProfileHighlight').each(function() {
$(this).addClass('batteryProfileHighlightActive');
$(this).removeClass('batteryProfileHighlight');
});
$('.controlProfileHighlight').each(function() {
$(this).addClass('controlProfileHighlightActive');
$(this).removeClass('controlProfileHighlight');
});
} else {
$('.dropdown-dark #profilechange').removeClass('showProfileParams');
$('.dropdown-dark #batteryprofilechange').removeClass('showProfileParams');
$('.batteryProfileHighlightActive').each(function() {
$(this).addClass('batteryProfileHighlight');
$(this).removeClass('batteryProfileHighlightActive');
});
$('.controlProfileHighlightActive').each(function() {
$(this).addClass('controlProfileHighlight');
$(this).removeClass('controlProfileHighlightActive');
});
}
}
function catch_startup_time(startTime) {
var endTime = new Date().getTime(),
timeSpent = endTime - startTime;

View file

@ -35,7 +35,7 @@
"jquery-ui-npm": "1.12.0",
"marked": "^0.3.17",
"minimist": "^1.2.0",
"nw": "^0.50.3-sdk",
"nw": "^0.61.0",
"nw-dialog": "^1.0.7",
"openlayers": "^4.6.5",
"plotly": "^1.0.6",

View file

@ -8,41 +8,22 @@ viewBox="0 0 850 850"
<defs>
<style type="text/css">
<![CDATA[
.str0 {stroke:black;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str1 {stroke:#00A6FF;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str3 {stroke:#00E000;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str2 {stroke:red;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str4 {stroke:#FF7F00;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.fil4 {fill:#00A6FF}
.fil3 {fill:#00A6FF}
.fil1 {fill:#00E000}
.fil0 {fill:#999999}
.fil6 {fill:red}
.fil3 {fill:#FF7F00}
.fil2 {fill:white}
.fil5 {fill:black;fill-rule:nonzero}
.fil7 {fill:white;fill-rule:nonzero}
.fil4 {fill:red}
.fil2 {fill:#FF7F00}
.fil5 {fill:white;fill-rule:nonzero}
]]>
</style>
</defs>
<g id="Layer_x0020_1">
<metadata id="CorelCorpID_0Corel-Layer"/>
<path class="fil0" d="M258.88 767.6l148.41 0c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l148.41 0 -10 -73.61 -119.52 -25.32c6.72,-69.54 21.76,-183.85 24.95,-267.2l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 1.32,-93.85 -1.5,-129.58 -11.36,45.38 -37.14,69.99 -74,69.99 -36.86,0 -65.43,-27.83 -74,-69.99 -2.82,35.73 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 18.23,197.66 24.95,267.2l-119.52 25.32 -10 73.61z"/>
<path class="fil0" d="M258.88 767.6l148.41 0c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l148.41 0 -10 -73.61 -119.52 -25.32c6.72,-69.54 21.76,-183.85 24.95,-267.2l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 4.39,-94.22 -1.5,-129.58 -6.01,-36.11 -37.14,-74.01 -74,-74.01 -36.86,0 -67.99,37.9 -74,74.01 -5.89,35.36 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 18.23,197.66 24.95,267.2l-119.52 25.32 -10 73.61z"/>
<polygon class="fil1" points="572.59,412.03 792.63,439.04 792.63,370 572.59,343 "/>
<circle class="fil2 str0" cx="425" cy="82.02" r="70"/>
<polygon class="fil3" points="272.88,767.6 577.12,767.6 571.12,718.58 278.88,718.58 "/>
<path class="fil4" d="M425 839.54c0,0 -38.43,-227.94 0,-227.94 38.43,0 0,227.94 0,227.94z"/>
<path class="fil5" d="M393.05 105.15l-8.61 0 0 -34.58c0,-4.12 0.09,-7.4 0.3,-9.81 -0.57,0.57 -1.26,1.23 -2.08,1.94 -0.81,0.71 -3.55,2.95 -8.23,6.73l-4.31 -5.46 15.75 -12.37 7.18 0 0 53.55z"/>
<polygon id="_1" class="fil5" points="435.91,51.6 416,105.15 407.87,105.15 427.82,51.6 "/>
<path id="_2" class="fil5" d="M476.15 105.15l-36.3 0 0 -6.51 13.81 -13.89c4.08,-4.18 6.78,-7.13 8.11,-8.88 1.33,-1.75 2.3,-3.38 2.92,-4.92 0.61,-1.54 0.91,-3.19 0.91,-4.95 0,-2.42 -0.73,-4.33 -2.18,-5.72 -1.45,-1.38 -3.46,-2.08 -6.02,-2.08 -2.05,0 -4.04,0.37 -5.96,1.14 -1.92,0.75 -4.13,2.12 -6.66,4.09l-4.65 -5.67c2.99,-2.51 5.88,-4.29 8.69,-5.34 2.82,-1.05 5.8,-1.57 8.98,-1.57 4.97,0 8.97,1.3 11.97,3.9 3.02,2.6 4.52,6.1 4.52,10.48 0,2.43 -0.44,4.72 -1.31,6.89 -0.87,2.18 -2.19,4.42 -3.99,6.73 -1.8,2.3 -4.78,5.42 -8.97,9.35l-9.3 9.01 0 0.36 25.43 0 0 7.58z"/>
<rect class="fil2 str1" x="268.91" y="608.35" width="90" height="90"/>
<path class="fil5" d="M296.12 657.32c0,-20.95 8.53,-31.43 25.6,-31.43 2.69,0 4.97,0.21 6.82,0.63l0 7.15c-1.85,-0.54 -4,-0.8 -6.45,-0.8 -5.74,0 -10.05,1.53 -12.93,4.61 -2.89,3.09 -4.45,8.02 -4.69,14.81l0.44 0c1.15,-1.97 2.76,-3.51 4.84,-4.6 2.07,-1.09 4.51,-1.62 7.32,-1.62 4.87,0 8.64,1.48 11.35,4.47 2.72,2.98 4.08,7.01 4.08,12.11 0,5.63 -1.58,10.07 -4.71,13.33 -3.14,3.26 -7.42,4.89 -12.84,4.89 -3.84,0 -7.18,-0.93 -10,-2.77 -2.84,-1.85 -5.01,-4.53 -6.54,-8.06 -1.52,-3.52 -2.29,-7.77 -2.29,-12.72zm18.68 16.42c2.96,0 5.24,-0.95 6.84,-2.86 1.6,-1.9 2.4,-4.63 2.4,-8.16 0,-3.09 -0.75,-5.5 -2.25,-7.27 -1.52,-1.76 -3.77,-2.63 -6.77,-2.63 -1.86,0 -3.57,0.4 -5.13,1.18 -1.57,0.8 -2.79,1.89 -3.7,3.27 -0.9,1.38 -1.35,2.78 -1.35,4.23 0,3.44 0.93,6.35 2.8,8.7 1.87,2.37 4.26,3.54 7.16,3.54z"/>
<rect class="fil2 str2" x="96.18" y="455.06" width="90" height="90"/>
<path class="fil5" d="M158.46 515.13l-7.23 0 0 11.7 -8.39 0 0 -11.7 -24.47 0 0 -6.61 24.47 -35.39 8.39 0 0 34.88 7.23 0 0 7.12zm-15.62 -7.12l0 -13.45c0,-4.79 0.13,-8.7 0.37,-11.76l-0.29 0c-0.69,1.61 -1.76,3.57 -3.23,5.86l-13.3 19.35 16.45 0z"/>
<rect class="fil2 str3" x="663.55" y="455.06" width="90" height="90"/>
<path class="fil5" d="M708.78 493.38c5.4,0 9.68,1.43 12.83,4.29 3.15,2.86 4.72,6.76 4.72,11.7 0,5.71 -1.78,10.18 -5.36,13.39 -3.57,3.21 -8.66,4.82 -15.26,4.82 -5.98,0 -10.69,-0.96 -14.1,-2.9l0 -7.81c1.97,1.13 4.25,1.99 6.81,2.6 2.56,0.61 4.95,0.91 7.15,0.91 3.88,0 6.84,-0.86 8.86,-2.6 2.03,-1.72 3.04,-4.26 3.04,-7.61 0,-6.39 -4.07,-9.59 -12.24,-9.59 -1.15,0 -2.56,0.12 -4.25,0.35 -1.68,0.23 -3.16,0.49 -4.42,0.79l-3.85 -2.27 2.05 -26.17 27.84 0 0 7.65 -20.27 0 -1.2 13.25c0.85,-0.13 1.89,-0.31 3.13,-0.51 1.24,-0.19 2.75,-0.29 4.52,-0.29z"/>
<rect class="fil2 str4" x="617.8" y="726.17" width="90" height="90"/>
<path class="fil5" d="M680.15 756.7c0,3.4 -0.98,6.23 -2.96,8.48 -1.99,2.26 -4.76,3.77 -8.36,4.56l0 0.29c4.3,0.53 7.52,1.87 9.67,4.01 2.15,2.14 3.23,4.99 3.23,8.52 0,5.15 -1.83,9.14 -5.46,11.93 -3.64,2.8 -8.82,4.2 -15.53,4.2 -5.94,0 -10.95,-0.96 -15.02,-2.9l0 -7.66c2.27,1.12 4.67,1.98 7.21,2.6 2.55,0.61 4.98,0.91 7.34,0.91 4.15,0 7.24,-0.78 9.3,-2.31 2.05,-1.54 3.07,-3.92 3.07,-7.14 0,-2.86 -1.12,-4.96 -3.4,-6.31 -2.27,-1.34 -5.84,-2.02 -10.7,-2.02l-4.65 0 0 -6.97 4.73 0c8.55,0 12.82,-2.95 12.82,-8.86 0,-2.3 -0.75,-4.08 -2.24,-5.33 -1.48,-1.24 -3.68,-1.86 -6.6,-1.86 -2.02,0 -3.97,0.29 -5.86,0.86 -1.87,0.58 -4.1,1.69 -6.66,3.35l-4.21 -6c4.9,-3.61 10.61,-5.41 17.1,-5.41 5.4,0 9.61,1.16 12.64,3.47 3.03,2.33 4.54,5.52 4.54,9.59z"/>
<polygon class="fil6" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil7" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
<polygon class="fil2" points="272.88,767.6 577.12,767.6 571.12,718.58 278.88,718.58 "/>
<path class="fil3" d="M425 839.54c0,0 -38.43,-227.94 0,-227.94 38.43,0 0,227.94 0,227.94z"/>
<polygon class="fil4" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil5" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 5.9 KiB

After

Width:  |  Height:  |  Size: 1.9 KiB

Before After
Before After

View file

@ -8,38 +8,22 @@ viewBox="0 0 850 850"
<defs>
<style type="text/css">
<![CDATA[
.str0 {stroke:black;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str2 {stroke:#00E000;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str1 {stroke:red;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str3 {stroke:#FF7F00;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.fil1 {fill:#00E000}
.fil4 {fill:gray}
.fil3 {fill:gray}
.fil0 {fill:#999999}
.fil6 {fill:red}
.fil3 {fill:#FF7F00}
.fil2 {fill:white}
.fil5 {fill:black;fill-rule:nonzero}
.fil7 {fill:white;fill-rule:nonzero}
.fil4 {fill:red}
.fil2 {fill:#FF7F00}
.fil5 {fill:white;fill-rule:nonzero}
]]>
</style>
</defs>
<g id="Layer_x0020_1">
<metadata id="CorelCorpID_0Corel-Layer"/>
<path class="fil0" d="M258.88 767.6l148.41 0c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l148.41 0 -10 -73.61 -119.52 -25.32c6.72,-69.54 21.76,-183.85 24.95,-267.2l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 1.32,-93.85 -1.5,-129.58 -11.36,45.38 -37.14,69.99 -74,69.99 -36.86,0 -65.43,-27.83 -74,-69.99 -2.82,35.73 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 18.23,197.66 24.95,267.2l-119.52 25.32 -10 73.61z"/>
<path class="fil0" d="M258.88 767.6l148.41 0c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l148.41 0 -10 -73.61 -119.52 -25.32c6.72,-69.54 21.76,-183.85 24.95,-267.2l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 4.39,-94.22 -1.5,-129.58 -6.01,-36.11 -37.14,-74.01 -74,-74.01 -36.86,0 -67.99,37.9 -74,74.01 -5.89,35.36 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 18.23,197.66 24.95,267.2l-119.52 25.32 -10 73.61z"/>
<polygon class="fil1" points="572.59,412.03 792.63,439.04 792.63,370 572.59,343 "/>
<circle class="fil2 str0" cx="425" cy="82.02" r="70"/>
<polygon class="fil3" points="272.88,767.6 577.12,767.6 571.12,718.58 278.88,718.58 "/>
<path class="fil4" d="M425 839.54c0,0 -38.43,-227.94 0,-227.94 38.43,0 0,227.94 0,227.94z"/>
<path class="fil5" d="M393.05 105.15l-8.61 0 0 -34.58c0,-4.12 0.09,-7.4 0.3,-9.81 -0.57,0.57 -1.26,1.23 -2.08,1.94 -0.81,0.71 -3.55,2.95 -8.23,6.73l-4.31 -5.46 15.75 -12.37 7.18 0 0 53.55z"/>
<polygon id="_1" class="fil5" points="435.91,51.6 416,105.15 407.87,105.15 427.82,51.6 "/>
<path id="_2" class="fil5" d="M476.15 105.15l-36.3 0 0 -6.51 13.81 -13.89c4.08,-4.18 6.78,-7.13 8.11,-8.88 1.33,-1.75 2.3,-3.38 2.92,-4.92 0.61,-1.54 0.91,-3.19 0.91,-4.95 0,-2.42 -0.73,-4.33 -2.18,-5.72 -1.45,-1.38 -3.46,-2.08 -6.02,-2.08 -2.05,0 -4.04,0.37 -5.96,1.14 -1.92,0.75 -4.13,2.12 -6.66,4.09l-4.65 -5.67c2.99,-2.51 5.88,-4.29 8.69,-5.34 2.82,-1.05 5.8,-1.57 8.98,-1.57 4.97,0 8.97,1.3 11.97,3.9 3.02,2.6 4.52,6.1 4.52,10.48 0,2.43 -0.44,4.72 -1.31,6.89 -0.87,2.18 -2.19,4.42 -3.99,6.73 -1.8,2.3 -4.78,5.42 -8.97,9.35l-9.3 9.01 0 0.36 25.43 0 0 7.58z"/>
<rect class="fil2 str1" x="96.18" y="455.06" width="90" height="90"/>
<path class="fil5" d="M158.46 515.13l-7.23 0 0 11.7 -8.39 0 0 -11.7 -24.47 0 0 -6.61 24.47 -35.39 8.39 0 0 34.88 7.23 0 0 7.12zm-15.62 -7.12l0 -13.45c0,-4.79 0.13,-8.7 0.37,-11.76l-0.29 0c-0.69,1.61 -1.76,3.57 -3.23,5.86l-13.3 19.35 16.45 0z"/>
<rect class="fil2 str2" x="663.55" y="455.06" width="90" height="90"/>
<path class="fil5" d="M708.78 493.38c5.4,0 9.68,1.43 12.83,4.29 3.15,2.86 4.72,6.76 4.72,11.7 0,5.71 -1.78,10.18 -5.36,13.39 -3.57,3.21 -8.66,4.82 -15.26,4.82 -5.98,0 -10.69,-0.96 -14.1,-2.9l0 -7.81c1.97,1.13 4.25,1.99 6.81,2.6 2.56,0.61 4.95,0.91 7.15,0.91 3.88,0 6.84,-0.86 8.86,-2.6 2.03,-1.72 3.04,-4.26 3.04,-7.61 0,-6.39 -4.07,-9.59 -12.24,-9.59 -1.15,0 -2.56,0.12 -4.25,0.35 -1.68,0.23 -3.16,0.49 -4.42,0.79l-3.85 -2.27 2.05 -26.17 27.84 0 0 7.65 -20.27 0 -1.2 13.25c0.85,-0.13 1.89,-0.31 3.13,-0.51 1.24,-0.19 2.75,-0.29 4.52,-0.29z"/>
<rect class="fil2 str3" x="617.8" y="726.17" width="90" height="90"/>
<path class="fil5" d="M680.15 756.7c0,3.4 -0.98,6.23 -2.96,8.48 -1.99,2.26 -4.76,3.77 -8.36,4.56l0 0.29c4.3,0.53 7.52,1.87 9.67,4.01 2.15,2.14 3.23,4.99 3.23,8.52 0,5.15 -1.83,9.14 -5.46,11.93 -3.64,2.8 -8.82,4.2 -15.53,4.2 -5.94,0 -10.95,-0.96 -15.02,-2.9l0 -7.66c2.27,1.12 4.67,1.98 7.21,2.6 2.55,0.61 4.98,0.91 7.34,0.91 4.15,0 7.24,-0.78 9.3,-2.31 2.05,-1.54 3.07,-3.92 3.07,-7.14 0,-2.86 -1.12,-4.96 -3.4,-6.31 -2.27,-1.34 -5.84,-2.02 -10.7,-2.02l-4.65 0 0 -6.97 4.73 0c8.55,0 12.82,-2.95 12.82,-8.86 0,-2.3 -0.75,-4.08 -2.24,-5.33 -1.48,-1.24 -3.68,-1.86 -6.6,-1.86 -2.02,0 -3.97,0.29 -5.86,0.86 -1.87,0.58 -4.1,1.69 -6.66,3.35l-4.21 -6c4.9,-3.61 10.61,-5.41 17.1,-5.41 5.4,0 9.61,1.16 12.64,3.47 3.03,2.33 4.54,5.52 4.54,9.59z"/>
<polygon class="fil6" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil7" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
<polygon class="fil2" points="272.88,767.6 577.12,767.6 571.12,718.58 278.88,718.58 "/>
<path class="fil3" d="M425 839.54c0,0 -38.43,-227.94 0,-227.94 38.43,0 0,227.94 0,227.94z"/>
<polygon class="fil4" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil5" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 5 KiB

After

Width:  |  Height:  |  Size: 1.9 KiB

Before After
Before After

View file

@ -8,41 +8,22 @@ viewBox="0 0 850 850"
<defs>
<style type="text/css">
<![CDATA[
.str0 {stroke:black;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str4 {stroke:#00A6FF;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str2 {stroke:#00E000;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str1 {stroke:red;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str3 {stroke:#FF7F00;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.fil7 {fill:#00A6FF}
.fil5 {fill:#00A6FF}
.fil1 {fill:#00E000}
.fil0 {fill:#999999}
.fil4 {fill:red}
.fil6 {fill:#FF7F00}
.fil2 {fill:white}
.fil3 {fill:black;fill-rule:nonzero}
.fil5 {fill:white;fill-rule:nonzero}
.fil2 {fill:red}
.fil4 {fill:#FF7F00}
.fil3 {fill:white;fill-rule:nonzero}
]]>
</style>
</defs>
<g id="Layer_x0020_1">
<metadata id="CorelCorpID_0Corel-Layer"/>
<path class="fil0" d="M218.86 837.63l188.43 -70.03c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l188.43 70.03 -10 -93.62 -154.54 -105.35c6.72,-69.54 16.76,-153.84 19.95,-237.19l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 1.32,-93.85 -1.5,-129.58 -11.36,45.38 -37.14,69.99 -74,69.99 -36.86,0 -65.43,-27.83 -74,-69.99 -2.82,35.73 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 13.23,167.65 19.95,237.19l-154.54 105.35 -10 93.62z"/>
<path class="fil0" d="M218.86 837.63l188.43 -70.03c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l188.43 70.03 -10 -93.62 -154.54 -105.35c6.72,-69.54 16.76,-153.84 19.95,-237.19l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 4.39,-94.22 -1.5,-129.58 -6.01,-36.11 -37.14,-74.01 -74,-74.01 -36.86,0 -67.99,37.9 -74,74.01 -5.89,35.36 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 13.23,167.65 19.95,237.19l-154.54 105.35 -10 93.62z"/>
<polygon class="fil1" points="572.59,412.03 792.63,439.04 792.63,370 572.59,343 "/>
<circle class="fil2 str0" cx="425" cy="82.02" r="70"/>
<path class="fil3" d="M393.05 105.15l-8.61 0 0 -34.58c0,-4.12 0.09,-7.4 0.3,-9.81 -0.57,0.57 -1.26,1.23 -2.08,1.94 -0.81,0.71 -3.55,2.95 -8.23,6.73l-4.31 -5.46 15.75 -12.37 7.18 0 0 53.55z"/>
<polygon id="_1" class="fil3" points="435.91,51.6 416,105.15 407.87,105.15 427.82,51.6 "/>
<path id="_2" class="fil3" d="M476.15 105.15l-36.3 0 0 -6.51 13.81 -13.89c4.08,-4.18 6.78,-7.13 8.11,-8.88 1.33,-1.75 2.3,-3.38 2.92,-4.92 0.61,-1.54 0.91,-3.19 0.91,-4.95 0,-2.42 -0.73,-4.33 -2.18,-5.72 -1.45,-1.38 -3.46,-2.08 -6.02,-2.08 -2.05,0 -4.04,0.37 -5.96,1.14 -1.92,0.75 -4.13,2.12 -6.66,4.09l-4.65 -5.67c2.99,-2.51 5.88,-4.29 8.69,-5.34 2.82,-1.05 5.8,-1.57 8.98,-1.57 4.97,0 8.97,1.3 11.97,3.9 3.02,2.6 4.52,6.1 4.52,10.48 0,2.43 -0.44,4.72 -1.31,6.89 -0.87,2.18 -2.19,4.42 -3.99,6.73 -1.8,2.3 -4.78,5.42 -8.97,9.35l-9.3 9.01 0 0.36 25.43 0 0 7.58z"/>
<rect class="fil2 str1" x="96.18" y="455.06" width="90" height="90"/>
<path class="fil3" d="M154.53 485.6c0,3.4 -0.99,6.22 -2.96,8.47 -1.99,2.26 -4.76,3.78 -8.36,4.56l0 0.29c4.3,0.54 7.52,1.88 9.67,4.01 2.15,2.14 3.23,4.99 3.23,8.53 0,5.15 -1.83,9.14 -5.47,11.92 -3.63,2.8 -8.81,4.2 -15.52,4.2 -5.94,0 -10.95,-0.96 -15.03,-2.9l0 -7.66c2.28,1.13 4.68,1.99 7.22,2.6 2.55,0.61 4.98,0.91 7.33,0.91 4.15,0 7.25,-0.77 9.3,-2.31 2.05,-1.54 3.08,-3.91 3.08,-7.14 0,-2.86 -1.13,-4.96 -3.4,-6.31 -2.28,-1.34 -5.84,-2.01 -10.7,-2.01l-4.65 0 0 -6.98 4.72 0c8.55,0 12.83,-2.95 12.83,-8.86 0,-2.3 -0.75,-4.07 -2.24,-5.32 -1.49,-1.24 -3.69,-1.87 -6.6,-1.87 -2.02,0 -3.97,0.29 -5.86,0.87 -1.88,0.57 -4.1,1.68 -6.66,3.35l-4.22 -6c4.9,-3.62 10.62,-5.42 17.1,-5.42 5.4,0 9.62,1.17 12.65,3.48 3.03,2.32 4.54,5.51 4.54,9.59z"/>
<rect class="fil2 str2" x="663.55" y="455.06" width="90" height="90"/>
<path class="fil3" d="M728.83 515.13l-7.22 0 0 11.7 -8.39 0 0 -11.7 -24.47 0 0 -6.61 24.47 -35.39 8.39 0 0 34.88 7.22 0 0 7.12zm-15.61 -7.12l0 -13.45c0,-4.79 0.13,-8.7 0.36,-11.76l-0.28 0c-0.69,1.61 -1.77,3.57 -3.23,5.86l-13.3 19.35 16.45 0z"/>
<rect class="fil2 str3" x="108.12" y="744.93" width="90" height="90"/>
<path class="fil3" d="M154.35 783.25c5.4,0 9.67,1.42 12.82,4.28 3.15,2.87 4.73,6.77 4.73,11.7 0,5.72 -1.79,10.18 -5.36,13.39 -3.58,3.21 -8.67,4.83 -15.27,4.83 -5.97,0 -10.68,-0.97 -14.1,-2.9l0 -7.82c1.98,1.13 4.25,1.99 6.82,2.6 2.56,0.62 4.95,0.92 7.15,0.92 3.87,0 6.83,-0.87 8.86,-2.6 2.02,-1.73 3.04,-4.27 3.04,-7.62 0,-6.39 -4.08,-9.58 -12.24,-9.58 -1.15,0 -2.56,0.11 -4.25,0.34 -1.69,0.23 -3.16,0.49 -4.43,0.79l-3.85 -2.27 2.05 -26.16 27.84 0 0 7.65 -20.26 0 -1.2 13.24c0.85,-0.13 1.89,-0.31 3.12,-0.51 1.24,-0.18 2.75,-0.28 4.53,-0.28z"/>
<polygon class="fil4" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil5" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
<polygon class="fil6" points="218.86,837.63 387.28,775.04 373.79,711.02 226.54,765.74 "/>
<polygon class="fil7" points="631.14,837.63 462.72,775.04 476.21,711.02 623.46,765.74 "/>
<rect class="fil2 str4" x="653.12" y="744.93" width="90" height="90"/>
<path class="fil3" d="M681.33 793.9c0,-20.96 8.53,-31.43 25.6,-31.43 2.69,0 4.96,0.21 6.82,0.63l0 7.14c-1.86,-0.53 -4,-0.79 -6.45,-0.79 -5.74,0 -10.05,1.53 -12.93,4.61 -2.89,3.08 -4.45,8.02 -4.69,14.81l0.44 0c1.15,-1.98 2.76,-3.51 4.84,-4.6 2.07,-1.09 4.51,-1.62 7.32,-1.62 4.87,0 8.64,1.48 11.35,4.47 2.72,2.98 4.08,7.01 4.08,12.11 0,5.63 -1.58,10.07 -4.71,13.33 -3.14,3.26 -7.42,4.89 -12.84,4.89 -3.84,0 -7.18,-0.93 -10,-2.77 -2.84,-1.85 -5.01,-4.54 -6.54,-8.06 -1.52,-3.53 -2.29,-7.77 -2.29,-12.72zm18.68 16.42c2.96,0 5.24,-0.95 6.84,-2.86 1.59,-1.9 2.4,-4.63 2.4,-8.16 0,-3.09 -0.75,-5.51 -2.25,-7.27 -1.52,-1.76 -3.77,-2.63 -6.77,-2.63 -1.86,0 -3.57,0.4 -5.14,1.18 -1.56,0.8 -2.78,1.89 -3.69,3.27 -0.9,1.38 -1.35,2.78 -1.35,4.23 0,3.44 0.93,6.35 2.79,8.7 1.88,2.37 4.27,3.54 7.17,3.54z"/>
<polygon class="fil2" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil3" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
<polygon class="fil4" points="218.86,837.63 387.28,775.04 373.79,711.02 226.54,765.74 "/>
<polygon class="fil5" points="631.14,837.63 462.72,775.04 476.21,711.02 623.46,765.74 "/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 6 KiB

After

Width:  |  Height:  |  Size: 1.9 KiB

Before After
Before After

View file

@ -8,37 +8,21 @@ viewBox="0 0 850 850"
<defs>
<style type="text/css">
<![CDATA[
.str0 {stroke:black;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str3 {stroke:#00E000;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str2 {stroke:red;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str1 {stroke:#FF7F00;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.fil6 {fill:#00E000}
.fil4 {fill:#00E000}
.fil0 {fill:#999999}
.fil5 {fill:red}
.fil3 {fill:red}
.fil1 {fill:#FF7F00}
.fil2 {fill:white}
.fil3 {fill:black;fill-rule:nonzero}
.fil4 {fill:white;fill-rule:nonzero}
.fil2 {fill:white;fill-rule:nonzero}
]]>
</style>
</defs>
<g id="Layer_x0020_1">
<metadata id="CorelCorpID_0Corel-Layer"/>
<path class="fil0" d="M218.86 837.63l188.43 -70.03c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l188.43 70.03 -10 -93.62 -154.54 -105.35c6.72,-69.54 16.76,-153.84 19.95,-237.19l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 1.32,-93.85 -1.5,-129.58 -11.36,45.38 -37.14,69.99 -74,69.99 -36.86,0 -65.43,-27.83 -74,-69.99 -2.82,35.73 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 13.23,167.65 19.95,237.19l-154.54 105.35 -10 93.62z"/>
<path class="fil0" d="M218.86 837.63l188.43 -70.03c5.38,21.31 11.3,33.52 17.71,33.52 6.41,0 12.33,-12.21 17.71,-33.52l188.43 70.03 -10 -93.62 -154.54 -105.35c6.72,-69.54 16.76,-153.84 19.95,-237.19l326.09 40.02 0 -169.86 -312.14 -60.03c0.45,-66.81 4.39,-94.22 -1.5,-129.58 -6.01,-36.11 -37.14,-74.01 -74,-74.01 -36.86,0 -67.99,37.9 -74,74.01 -5.89,35.36 -1.95,62.77 -1.5,129.58l-312.14 60.03 0 169.86 326.09 -40.02c3.19,83.35 13.23,167.65 19.95,237.19l-154.54 105.35 -10 93.62z"/>
<polygon class="fil1" points="572.59,412.03 792.63,439.04 792.63,370 572.59,343 "/>
<circle class="fil2 str0" cx="425" cy="82.02" r="70"/>
<path class="fil3" d="M393.05 105.15l-8.61 0 0 -34.58c0,-4.12 0.09,-7.4 0.3,-9.81 -0.57,0.57 -1.26,1.23 -2.08,1.94 -0.81,0.71 -3.55,2.95 -8.23,6.73l-4.31 -5.46 15.75 -12.37 7.18 0 0 53.55z"/>
<polygon id="_1" class="fil3" points="435.91,51.6 416,105.15 407.87,105.15 427.82,51.6 "/>
<path id="_2" class="fil3" d="M476.15 105.15l-36.3 0 0 -6.51 13.81 -13.89c4.08,-4.18 6.78,-7.13 8.11,-8.88 1.33,-1.75 2.3,-3.38 2.92,-4.92 0.61,-1.54 0.91,-3.19 0.91,-4.95 0,-2.42 -0.73,-4.33 -2.18,-5.72 -1.45,-1.38 -3.46,-2.08 -6.02,-2.08 -2.05,0 -4.04,0.37 -5.96,1.14 -1.92,0.75 -4.13,2.12 -6.66,4.09l-4.65 -5.67c2.99,-2.51 5.88,-4.29 8.69,-5.34 2.82,-1.05 5.8,-1.57 8.98,-1.57 4.97,0 8.97,1.3 11.97,3.9 3.02,2.6 4.52,6.1 4.52,10.48 0,2.43 -0.44,4.72 -1.31,6.89 -0.87,2.18 -2.19,4.42 -3.99,6.73 -1.8,2.3 -4.78,5.42 -8.97,9.35l-9.3 9.01 0 0.36 25.43 0 0 7.58z"/>
<rect class="fil2 str1" x="96.18" y="455.06" width="90" height="90"/>
<path class="fil3" d="M154.53 485.6c0,3.4 -0.99,6.22 -2.96,8.47 -1.99,2.26 -4.76,3.78 -8.36,4.56l0 0.29c4.3,0.54 7.52,1.88 9.67,4.01 2.15,2.14 3.23,4.99 3.23,8.53 0,5.15 -1.83,9.14 -5.47,11.92 -3.63,2.8 -8.81,4.2 -15.52,4.2 -5.94,0 -10.95,-0.96 -15.03,-2.9l0 -7.66c2.28,1.13 4.68,1.99 7.22,2.6 2.55,0.61 4.98,0.91 7.33,0.91 4.15,0 7.25,-0.77 9.3,-2.31 2.05,-1.54 3.08,-3.91 3.08,-7.14 0,-2.86 -1.13,-4.96 -3.4,-6.31 -2.28,-1.34 -5.84,-2.01 -10.7,-2.01l-4.65 0 0 -6.98 4.72 0c8.55,0 12.83,-2.95 12.83,-8.86 0,-2.3 -0.75,-4.07 -2.24,-5.32 -1.49,-1.24 -3.69,-1.87 -6.6,-1.87 -2.02,0 -3.97,0.29 -5.86,0.87 -1.88,0.57 -4.1,1.68 -6.66,3.35l-4.22 -6c4.9,-3.62 10.62,-5.42 17.1,-5.42 5.4,0 9.62,1.17 12.65,3.48 3.03,2.32 4.54,5.51 4.54,9.59z"/>
<rect class="fil2 str2" x="108.12" y="744.93" width="90" height="90"/>
<path class="fil3" d="M174.4 805l-7.23 0 0 11.7 -8.38 0 0 -11.7 -24.48 0 0 -6.62 24.48 -35.38 8.38 0 0 34.87 7.23 0 0 7.13zm-15.61 -7.13l0 -13.45c0,-4.79 0.12,-8.7 0.36,-11.76l-0.29 0c-0.69,1.61 -1.76,3.57 -3.22,5.86l-13.3 19.35 16.45 0z"/>
<polygon class="fil1" points="57.37,439.04 277.41,412.03 277.41,343 57.37,370 "/>
<path class="fil4" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
<polygon class="fil5" points="218.86,837.63 387.28,775.04 373.79,711.02 226.54,765.74 "/>
<polygon class="fil6" points="631.14,837.63 462.72,775.04 476.21,711.02 623.46,765.74 "/>
<rect class="fil2 str3" x="653.12" y="744.93" width="90" height="90"/>
<path class="fil3" d="M699.35 783.25c5.4,0 9.67,1.42 12.82,4.28 3.15,2.87 4.73,6.77 4.73,11.7 0,5.72 -1.79,10.18 -5.37,13.39 -3.57,3.21 -8.66,4.83 -15.26,4.83 -5.98,0 -10.69,-0.97 -14.1,-2.9l0 -7.82c1.97,1.13 4.25,1.99 6.81,2.6 2.57,0.62 4.95,0.92 7.15,0.92 3.88,0 6.84,-0.87 8.86,-2.6 2.03,-1.73 3.04,-4.27 3.04,-7.62 0,-6.39 -4.07,-9.58 -12.23,-9.58 -1.16,0 -2.57,0.11 -4.25,0.34 -1.69,0.23 -3.17,0.49 -4.43,0.79l-3.85 -2.27 2.05 -26.16 27.84 0 0 7.65 -20.26 0 -1.2 13.24c0.84,-0.13 1.88,-0.31 3.12,-0.51 1.24,-0.18 2.75,-0.28 4.53,-0.28z"/>
<path class="fil2" d="M405.45 376.22l0 -84.15 -27.27 0 46.82 -84.15 46.82 84.15 -27.27 0 0 84.15 -39.1 0zm0 -42.08m-13.64 -42.07m9.78 -42.08m46.82 0m9.77 42.08m-13.63 42.07m-19.55 42.08"/>
<polygon class="fil3" points="218.86,837.63 387.28,775.04 373.79,711.02 226.54,765.74 "/>
<polygon class="fil4" points="631.14,837.63 462.72,775.04 476.21,711.02 623.46,765.74 "/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 5 KiB

After

Width:  |  Height:  |  Size: 1.9 KiB

Before After
Before After

View file

@ -8,31 +8,18 @@ viewBox="0 0 850 850"
<defs>
<style type="text/css">
<![CDATA[
.str0 {stroke:black;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str2 {stroke:#00E000;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.str1 {stroke:red;stroke-width:10;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:22.9256}
.fil3 {fill:#00E000}
.fil2 {fill:#999999}
.fil4 {fill:red}
.fil0 {fill:white}
.fil1 {fill:black;fill-rule:nonzero}
.fil5 {fill:white;fill-rule:nonzero}
.fil1 {fill:#00E000}
.fil0 {fill:#999999}
.fil2 {fill:red}
.fil3 {fill:white;fill-rule:nonzero}
]]>
</style>
</defs>
<g id="Layer_x0020_1">
<metadata id="CorelCorpID_0Corel-Layer"/>
<circle class="fil0 str0" cx="425" cy="500.92" r="70"/>
<path class="fil1" d="M393.05 524.05l-8.61 0 0 -34.57c0,-4.13 0.1,-7.4 0.3,-9.81 -0.57,0.57 -1.25,1.22 -2.08,1.93 -0.81,0.72 -3.55,2.95 -8.22,6.74l-4.32 -5.46 15.75 -12.38 7.18 0 0 53.55z"/>
<polygon id="_1" class="fil1" points="435.91,470.5 416,524.05 407.87,524.05 427.82,470.5 "/>
<path id="_2" class="fil1" d="M476.15 524.05l-36.3 0 0 -6.51 13.81 -13.89c4.07,-4.17 6.77,-7.12 8.11,-8.87 1.33,-1.75 2.3,-3.39 2.91,-4.93 0.62,-1.53 0.92,-3.18 0.92,-4.95 0,-2.41 -0.73,-4.32 -2.18,-5.71 -1.45,-1.39 -3.46,-2.09 -6.02,-2.09 -2.05,0 -4.04,0.38 -5.97,1.14 -1.91,0.75 -4.12,2.13 -6.65,4.1l-4.65 -5.67c2.99,-2.52 5.88,-4.29 8.69,-5.34 2.81,-1.05 5.8,-1.58 8.98,-1.58 4.97,0 8.97,1.3 11.97,3.9 3.01,2.6 4.51,6.1 4.51,10.49 0,2.43 -0.43,4.71 -1.3,6.89 -0.87,2.17 -2.2,4.41 -4,6.72 -1.8,2.3 -4.77,5.43 -8.96,9.35l-9.3 9.02 0 0.36 25.43 0 0 7.57z"/>
<rect class="fil0 str1" x="108.12" y="583.6" width="90" height="90"/>
<path class="fil1" d="M170.47 614.13c0,3.4 -0.98,6.23 -2.96,8.48 -1.99,2.26 -4.76,3.77 -8.36,4.56l0 0.29c4.3,0.54 7.52,1.87 9.67,4.01 2.15,2.14 3.23,4.99 3.23,8.53 0,5.15 -1.83,9.13 -5.46,11.92 -3.64,2.8 -8.82,4.2 -15.53,4.2 -5.94,0 -10.95,-0.96 -15.02,-2.9l0 -7.66c2.27,1.12 4.67,1.99 7.21,2.6 2.55,0.61 4.99,0.91 7.34,0.91 4.15,0 7.25,-0.77 9.3,-2.31 2.05,-1.54 3.07,-3.91 3.07,-7.14 0,-2.86 -1.12,-4.96 -3.4,-6.31 -2.27,-1.34 -5.84,-2.01 -10.7,-2.01l-4.65 0 0 -6.98 4.73 0c8.55,0 12.82,-2.95 12.82,-8.86 0,-2.3 -0.75,-4.08 -2.24,-5.33 -1.48,-1.23 -3.68,-1.86 -6.6,-1.86 -2.02,0 -3.97,0.29 -5.86,0.86 -1.87,0.58 -4.1,1.69 -6.66,3.35l-4.21 -6c4.9,-3.61 10.61,-5.41 17.1,-5.41 5.4,0 9.61,1.16 12.65,3.48 3.02,2.32 4.53,5.51 4.53,9.58z"/>
<path class="fil2" d="M490.19 412.07l345.42 169.55 0 -179.94 -376.74 -217.33c-18.77,-10.83 -46,-10.37 -65.03,0l-379.45 206.74 0 179.93 345.42 -158.95 130.38 0z"/>
<polygon class="fil3" points="581.33,456.8 814.41,571.21 814.41,498.09 581.33,383.68 "/>
<polygon class="fil4" points="35.59,561.27 268.67,454.01 268.67,380.88 35.59,488.14 "/>
<path class="fil5" d="M404.3 385.32l0 -89.14 -28.9 0 49.6 -89.14 49.6 89.14 -28.9 0 0 89.14 -41.4 0zm0 -44.57m-14.45 -44.57m10.35 -44.57m49.6 0m10.35 44.57m-14.45 44.57m-20.7 44.57"/>
<rect class="fil0 str2" x="653.12" y="583.6" width="90" height="90"/>
<path class="fil1" d="M719.39 643.67l-7.22 0 0 11.7 -8.39 0 0 -11.7 -24.47 0 0 -6.61 24.47 -35.39 8.39 0 0 34.88 7.22 0 0 7.12zm-15.61 -7.12l0 -13.45c0,-4.79 0.13,-8.7 0.36,-11.77l-0.28 0c-0.69,1.62 -1.76,3.58 -3.23,5.87l-13.3 19.35 16.45 0z"/>
<path class="fil0" d="M490.19 412.07l345.42 169.55 0 -179.94 -376.74 -217.33c-18.77,-10.83 -46,-10.37 -65.03,0l-379.45 206.74 0 179.93 345.42 -158.95 130.38 0z"/>
<polygon class="fil1" points="581.33,456.8 814.41,571.21 814.41,498.09 581.33,383.68 "/>
<polygon class="fil2" points="35.59,561.27 268.67,454.01 268.67,380.88 35.59,488.14 "/>
<path class="fil3" d="M404.3 385.32l0 -89.14 -28.9 0 49.6 -89.14 49.6 89.14 -28.9 0 0 89.14 -41.4 0zm0 -44.57m-14.45 -44.57m10.35 -44.57m49.6 0m10.35 44.57m-14.45 44.57m-20.7 44.57"/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 3.7 KiB

After

Width:  |  Height:  |  Size: 1.3 KiB

Before After
Before After

View file

@ -6665,47 +6665,47 @@ MAX7456
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000101
01010101
01000101
00100001
01010101
00100001
00101000
01010100
10100001
01001010
00010010
10000101
01001010
10001010
10000101
01010010
10101010
00010101
01010010
10101010
00000000
00010101
01010100
10101000
01010101
10101010
10000101
01010100
10101000
01010101
01010101
00100001
01010101
01010101
00100001
01010101
01010101
01000101
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10101010
10000101
01010100
10101010
10000101
01010101
00000000
00010101
01010101
01010101
01010101

Binary file not shown.

Before

Width:  |  Height:  |  Size: 12 KiB

After

Width:  |  Height:  |  Size: 12 KiB

Before After
Before After

Binary file not shown.

Before

Width:  |  Height:  |  Size: 220 B

After

Width:  |  Height:  |  Size: 1.6 KiB

Before After
Before After

View file

@ -112,7 +112,7 @@
}
.dropdown-dark {
background: #636363; /* NEW2 */
background: #636363; /* NEW2 */
background: #3e403f; /* NEW */
border-color: #111 #0a0a0a black;
@ -123,11 +123,7 @@
-webkit-box-shadow: inset 0 1px rgba(255, 255, 255, 0.1), 0 1px 1px rgba(0, 0, 0, 0.2);
box-shadow: inset 0 1px rgba(255, 255, 255, 0.1), 0 1px 1px rgba(0, 0, 0, 0.2);
color:#a6a6a6;
text-shadow:0px 1px rgba(0, 0, 0, 0.25);
text-shadow:0px 1px rgba(0, 0, 0, 0.25);
}
.dropdown-dark:before {
border-bottom-color: #aaa;
@ -143,9 +139,17 @@
}
.dropdown-dark .dropdown-select:focus {
color: #fff;
color: #fff !important;
}
.dropdown-dark .dropdown-select > option {
background: #56ab1a;
text-shadow: 0 1px rgba(0, 0, 0, 0.4);
}
.dropdown-dark #profilechange.showProfileParams {
color: #d5ebfe;
}
.dropdown-dark #batteryprofilechange.showProfileParams {
color: #fef2d5;
}

View file

@ -0,0 +1,7 @@
.tab-advanced-tuning .config-section select, .tab-advanced-tuning .spacer_box div input {
margin-right: 0 !important;
}
.tab-advanced-tuning .config-section .checkbox .switchery {
margin-right: 63px !important;
}

View file

@ -28,19 +28,19 @@
text-align: left;
border: 1px solid silver;
border-radius: 3px;
margin-right: 11px;
font-size: 12px;
font-weight: normal;
}
.config-section .number input,
.config-section .checkbox input,
.tab-configuration .number input {
width: 106px;
}
.config-section .string input,
.tab-configuration .string input {
width: 130px;
width: 106px;
}
.tab-configuration .disabled {
@ -49,7 +49,7 @@
.config-section input,
.tab-configuration input {
float: left;
/*float: left;*/
}
.config-section .spacer_box,
@ -138,9 +138,7 @@ hr {
}
.tab-configuration .mixerPreview img {
width: 90%;
height: 90%;
padding: 5%;
width: 175px;
}
.tab-configuration .gui_box {
@ -185,6 +183,12 @@ hr {
width: 110px;
}
.tab-configuration #magalign {
width: 111px;
height: 22px;
margin-right: 4px;
}
@media only screen and (max-width: 1055px) , only screen and (max-device-width: 1055px) {
.tab-configuration .gui_box span {
line-height: 17px;
@ -211,7 +215,12 @@ hr {
.config-section .radio,
.config-section .number {
position: relative;
height: 22px;
min-height: 22px;
}
.config-section .select select,
.config-section .number input {
vertical-align: top;
}
.config-section .checkbox label,
@ -220,8 +229,8 @@ hr {
}
.config-section label {
position: absolute;
left: 118px;
display: inline-block;
width: calc(100% - 162px);
}
.config-section .radio label {
@ -243,9 +252,21 @@ hr {
}
.config-section select {
width: 110px;
width: 111px;
height: 22px;
margin-right: 4px;
}
.config-section .helpicon {
margin-top: 3px;
}
.config-section .unit_wrapper {
vertical-align: top;
}
.config-section .checkbox .switchery {
margin-right: 72px;
vertical-align: top;
margin-top: 3px;
}

View file

@ -26,7 +26,6 @@
text-align: left;
border: 1px solid silver;
border-radius: 3px;
margin-right: 11px;
font-size: 12px;
font-weight: normal;
}
@ -253,10 +252,12 @@
height: 90px;
}
.tab-failsafe .minimumDistance {
width: 100px !important;
padding-left: 3px;
margin-right: 11px;
.tab-failsafe input {
width: 75px !important;
}
.tab-failsafe select {
width: 79px;
}
@media only screen and (max-width: 1055px) , only screen and (max-device-width: 1055px) {

View file

@ -271,7 +271,6 @@
text-align: left;
border: 1px solid silver;
border-radius: 3px;
margin-right: 11px;
margin-bottom: 5px;
font-size: 12px;
font-weight: normal;

View file

@ -113,6 +113,10 @@
border-top-right-radius: 0;
}
.tab-gps .config-section .checkbox .switchery {
margin-right: 68px;
}
#gps-map {
height: 400px;
width: 100%;

View file

@ -74,6 +74,12 @@
border-color: rgb(52, 155, 255);
}
.tab-led-strip .gPoint.function-h { /* Channel */
background: skyblue;
box-shadow: inset 0 0 30px rgba(0, 0, 0, .7);
border-color: black;
}
.tab-led-strip .gPoint.function-c .overlay-color,
.tab-led-strip .gPoint.function-r .overlay-color {
float: left;
@ -210,6 +216,7 @@
.tab-led-strip .select .function-g { background: green;}
/* .tab-led-strip .select .function-b { background: white; color:black;} */
.tab-led-strip .select .function-r { background: #acacac;}
.tab-led-strip .select .function-h { background: skyblue;}
.tab-led-strip .select .functionSelect option {
background: white;

View file

@ -2,6 +2,8 @@
position: absolute;
right: 0;
bottom: 1em;
margin-left: 185px;
width: calc(100% - 175px);
}
.mixer-load-button > div {
@ -95,4 +97,25 @@
.mixer-fixed-value-col {
display: none;
}
#needToUpdateMixerMessage {
margin-bottom: 5px;
}
.outputImageNumber {
position: absolute;
background-color: #FFF;
font-family: 'open_sansbold', Arial, serif;
width: 18px;
height: 18px;
border: 2.5px solid #ff00ff;
border-radius: 4px;
}
.outputImageNumber.isMotor {
width: 29px;
height: 29px;
line-height: 27px;
border-radius: 20px;
}

View file

@ -455,4 +455,12 @@
.tab-servos .short {
width: 32px;
}
}
.tab-motors .config-section .checkbox .switchery {
margin-right: 68px;
}
.tab-motors .config-section .number input {
margin-right: 4px;
}

View file

@ -295,4 +295,14 @@
pointer-events: none;
text-shadow: none;
opacity: 0.5;
}
.tab-onboard_logging .leftWrapper {
float: left;
width: calc(50% - 20px);
}
.tab-onboard_logging .rightWrapper {
float: right;
width: calc(50%);
}

View file

@ -477,25 +477,23 @@ button {
}
.tab-osd .settings input {
width: 55px;
width: 75px;
padding-left: 3px;
height: 18px;
line-height: 20px;
text-align: left;
border: 1px solid silver;
border-radius: 3px;
margin-right: 11px;
font-size: 11px;
font-weight: normal;
}
.tab-osd .settings select {
width: 75px;
margin-right: 11px;
width: 80px;
}
.tab-osd .settings .switchery {
margin-right: 25px;
margin-right: 33px;
}
.tab-osd .settings .djiCraftNameElements {
@ -531,4 +529,17 @@ button {
float: right;
width: auto !important;
margin-right: 0 !important;
}
.tab-osd label > .i18n-replaced {
display: inline-block;
left: 108px;
width: calc(100% - 110px);
}
.tab-osd .settings select,
.tab-osd .settings input,
.tab-osd .osd_settings .switchery,
.tab-osd .unit_wrapper {
vertical-align: top;
}

View file

@ -1,11 +1,14 @@
.rate-tpa_input {
margin: 4px;
width: 5em;
width: 150px;
height: 20px;
line-height: 20px;
border: 1px solid silver;
border-radius: 3px;
padding-left: 3px;
text-align: left;
font-size: 12px;
font-weight: normal;
display: inline-block;
line-height: 20px;
text-align: right;
}
.settings-table.settings-table--inav td,
@ -75,6 +78,16 @@
border-top-right-radius: 5px;
}
.settings-table tr:last-child th {
border-bottom-left-radius: 5px;
border-bottom: none;
}
.settings-table tr:last-child td {
border-bottom-right-radius: 5px;
border-bottom: none;
}
.settings-table {
/*border: 0px solid #ccc; */
margin-bottom: 10px;
@ -294,6 +307,12 @@
border-bottom: 0;
}
.tab-pid_tuning .pidTuning_number {
clear: left;
padding: 4px;
float: left;
}
.tab-pid_tuning .number input {
width: 50px;
padding-left: 3px;
@ -302,7 +321,6 @@
text-align: left;
border: 1px solid silver;
border-radius: 3px;
margin-right: 11px;
font-weight: normal;
}

View file

@ -1,75 +0,0 @@
.tab-transponder .spacer_box {
padding-bottom: 10px;
float: left;
width: calc(100% - 20px);
}
.tab-transponder .text input {
width: 100px;
padding-left: 3px;
height: 20px;
line-height: 20px;
text-align: left;
border: 1px solid silver;
border-radius: 3px;
margin-right: 11px;
font-size: 12px;
font-weight: normal;
}
.tab-transponder .text .disabled {
width: 43px;
padding: 0 5px;
background-color: #ececec;
}
.tab-transponder .text span {
margin-left: 0;
}
.tab-transponder input {
float: left;
}
.tab-transponder span {
margin: 0;
}
.tab-transponder .text
{
margin-bottom: 5px;
clear: left;
padding-bottom: 5px;
border-bottom: 1px solid #ddd;
width: 100%;
float: left;
}
.tab-transponder .text:last-child {
border-bottom: none;
padding-bottom: 0;
margin-bottom: 0;
}
.tab-transponder .textspacer {
float: left;
width: 115px;
height: 21px;
}
.tab-transponder .gui_box span {
font-style: normal;
font-family: 'open_sansregular', Arial,serif;
line-height: 19px;
color: #4F4F4F;
font-size: 11px;
}
.require-transponder-supported,
.tab-transponder.transponder-supported .require-transponder-unsupported {
display: none;
}
.tab-transponder.transponder-supported .require-transponder-supported {
display: block;
}

View file

@ -11,12 +11,12 @@
</div>
<div class="spacer_box settings">
<div class="number">
<input type="number" id="launchIdleThr" data-setting="nav_fw_launch_idle_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<input type="number" id="launchIdleThr" data-unit="us" data-setting="nav_fw_launch_idle_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<label for="launchIdleThr"><span data-i18n="configurationLaunchIdleThr"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div>
</div>
<div class="number">
<input type="number" id="launchMaxAngle" data-setting="nav_fw_launch_max_angle" data-setting-multiplier="1" step="1" min="5" max="180" />
<input type="number" id="launchMaxAngle" data-unit="deg" data-setting="nav_fw_launch_max_angle" data-setting-multiplier="1" step="1" min="5" max="180" />
<label for="launchMaxAngle"><span data-i18n="configurationLaunchMaxAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div>
</div>
@ -26,7 +26,7 @@
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchVelocityHelp"></div>
</div>
<div class="number">
<input type="number" id="launchAccel" data-setting="nav_fw_launch_accel" data-setting-multiplier="1" step="1" min="1000" max="20000" />
<input type="number" id="launchAccel" data-unit="cmss" data-setting="nav_fw_launch_accel" data-setting-multiplier="1" step="1" min="1000" max="20000" />
<label for="launchAccel"><span data-i18n="configurationLaunchAccel"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchAccelHelp"></div>
</div>
@ -51,12 +51,12 @@
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div>
</div>
<div class="number">
<input type="number" id="launchThr" data-setting="nav_fw_launch_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<input type="number" id="launchThr" data-unit="us" data-setting="nav_fw_launch_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<label for="launchThr"><span data-i18n="configurationLaunchThr"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div>
</div>
<div class="number">
<input type="number" id="launchClimbAngle" data-setting="nav_fw_launch_climb_angle" data-setting-multiplier="1" step="1" min="0" max="45" />
<input type="number" id="launchClimbAngle" data-unit="deg" data-setting="nav_fw_launch_climb_angle" data-setting-multiplier="1" step="1" min="0" max="45" />
<label for="launchClimbAngle"><span data-i18n="configurationLaunchClimbAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchClimbAngleHelp"></div>
</div>
@ -84,12 +84,12 @@
</div>
<div class="spacer_box">
<div class="number">
<input type="number" id="idlePower" data-setting="idle_power" data-setting-multiplier="1" step="1" min="0" max="65535" />
<input type="number" id="idlePower" data-unit="cw" data-setting="idle_power" data-setting-multiplier="1" step="1" min="0" max="65535" />
<label for="idlePower"><span data-i18n="idlePower"></span></label>
<div class="helpicon cf_tip" data-i18n_title="idlePowerHelp"></div>
</div>
<div class="number">
<input type="number" id="cruisePower" data-setting="cruise_power" data-setting-multiplier="1" step="1" min="0" max="4294967295" />
<input type="number" id="cruisePower" data-unit="cw" data-setting="cruise_power" data-setting-multiplier="1" step="1" min="0" max="4294967295" />
<label for="cruisePower"><span data-i18n="cruisePower"></span></label>
<div class="helpicon cf_tip" data-i18n_title="cruisePowerHelp"></div>
</div>
@ -99,7 +99,7 @@
<div class="helpicon cf_tip" data-i18n_title="cruiseSpeedHelp"></div>
</div>
<div class="number">
<input type="number" id="rthEnergyMargin" data-setting="rth_energy_margin" data-setting-multiplier="1" step="1" min="0" max="100" />
<input type="number" id="rthEnergyMargin" data-unit="percent" data-setting="rth_energy_margin" data-setting-multiplier="1" step="1" min="0" max="100" />
<label for="rthEnergyMargin"><span data-i18n="rthEnergyMargin"></span></label>
<div class="helpicon cf_tip" data-i18n_title="rthEnergyMarginHelp"></div>
</div>
@ -116,7 +116,7 @@
<div class="spacer_box">
<div class="number">
<input id="cruiseThrottle" type="number" data-setting="nav_fw_cruise_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<input id="cruiseThrottle" type="number" data-unit="us" data-setting="nav_fw_cruise_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<label for="cruiseThrottle"><span data-i18n="cruiseThrottle"></span></label>
</div>
@ -133,12 +133,12 @@
</div>
<div class="number">
<input id="minThrottle" type="number" data-setting="nav_fw_min_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<input id="minThrottle" type="number" data-unit="us" data-setting="nav_fw_min_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<label for="minThrottle"><span data-i18n="minThrottle"></span></label>
</div>
<div class="number">
<input id="maxThrottle" type="number" data-setting="nav_fw_max_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<input id="maxThrottle" type="number" data-unit="us" data-setting="nav_fw_max_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<label for="maxThrottle"><span data-i18n="maxThrottle"></span></label>
</div>
@ -149,7 +149,7 @@
</div>
<div class="number">
<input id="pitchToThrottleThreshold" type="number" data-setting="nav_fw_pitch2thr_threshold" data-setting-multiplier="1" step="1" min="0" max="900" />
<input id="pitchToThrottleThreshold" type="number" data-unit="decideg" data-setting="nav_fw_pitch2thr_threshold" data-setting-multiplier="1" step="1" min="0" max="900" />
<label for="pitchToThrottleThreshold"><span data-i18n="pitchToThrottleThreshold"></span></label>
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleThresholdHelp"></div>
</div>
@ -161,19 +161,19 @@
</div>
<div class="number">
<input id="maxBankAngle" type="number" data-setting="nav_fw_bank_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
<input id="maxBankAngle" type="number" data-unit="deg" data-setting="nav_fw_bank_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
<label for="maxBankAngle"><span data-i18n="maxBankAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="maxBankAngleHelp"></div>
</div>
<div class="number">
<input id="maxClimbAngle" type="number" data-setting="nav_fw_climb_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
<input id="maxClimbAngle" type="number" data-unit="deg" data-setting="nav_fw_climb_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
<label for="maxClimbAngle"><span data-i18n="maxClimbAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="maxClimbAngleHelp"></div>
</div>
<div class="number">
<input id="maxDiveAngle" type="number" data-setting="nav_fw_dive_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
<input id="maxDiveAngle" type="number" data-unit="deg" data-setting="nav_fw_dive_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
<label for="maxDiveAngle"><span data-i18n="maxDiveAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="maxDiveAngleHelp"></div>
</div>
@ -230,7 +230,7 @@
<div class="helpicon cf_tip" data-i18n_title="posholdMaxManualSpeedHelp"></div>
</div>
<div class="number">
<input id="max-bank-angle" type="number" data-setting="nav_mc_bank_angle" data-setting-multiplier="1" step="1" min="15" max="45" />
<input id="max-bank-angle" type="number" data-unit="deg" data-setting="nav_mc_bank_angle" data-setting-multiplier="1" step="1" min="15" max="45" />
<label for="max-bank-angle"><span data-i18n="posholdMaxBankAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="posholdMaxBankAngleHelp"></div>
</div>
@ -239,7 +239,7 @@
<label for="use-mid-throttle"><span data-i18n="posholdHoverMidThrottle"></span></label>
</div>
<div class="number">
<input id="hover-throttle" type="number" data-setting="nav_mc_hover_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<input id="hover-throttle" type="number" data-unit="us" data-setting="nav_mc_hover_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
<label for="hover-throttle"><span data-i18n="posholdHoverThrottle"></span></label>
</div>
<div class="checkbox">
@ -301,7 +301,7 @@
</div>
<div class="number">
<input id="brakingBankAngle" type="number" data-setting="nav_mc_braking_bank_angle" data-setting-multiplier="1" step="1" min="15" max="60" />
<input id="brakingBankAngle" type="number" data-unit="deg" data-setting="nav_mc_braking_bank_angle" data-setting-multiplier="1" step="1" min="15" max="60" />
<label for="brakingBankAngle"><span data-i18n="brakingBankAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="brakingBankAngleTip"></div>
</div>
@ -393,13 +393,13 @@
</div>
<div class="spacer_box">
<div class="number">
<input type="number" id="navManualClimbRate" data-unit="cms" data-setting="nav_manual_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
<input type="number" id="navManualClimbRate" data-unit="v-cms" data-setting="nav_manual_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
<label for="navManualClimbRate"><span data-i18n="navManualClimbRate"></span></label>
<div class="helpicon cf_tip" data-i18n_title="navManualClimbRateHelp"></div>
</div>
<div class="number">
<input type="number" id="navAutoClimbRate" data-unit="cms" data-setting="nav_auto_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
<input type="number" id="navAutoClimbRate" data-unit="v-cms" data-setting="nav_auto_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
<label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
<div class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
</div>
@ -427,35 +427,30 @@
</div>
</div>
<div class="config-setion gui_box grey">
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="autoLandingSettings"></div>
</div>
<div class="spacer_box">
<div class="number">
<input id="landMaxAltVspd" type="number" data-setting="nav_land_maxalt_vspd" data-setting-multiplier="1" step="1" min="100" max="2000" />
<input id="landMaxAltVspd" type="number" data-unit="v-cms" data-setting="nav_land_maxalt_vspd" data-setting-multiplier="1" step="1" min="100" max="2000" />
<label for="landMaxAltVspd"><span data-i18n="landMaxAltVspd"></span></label>
<div class="helpicon cf_tip" data-i18n_title="landMaxAltVspdHelp"></div>
</div>
<div class="number">
<input id="landSlowdownMaxAlt" type="number" data-setting="nav_land_slowdown_maxalt" data-setting-multiplier="1" step="1" min="500" max="4000" />
<input id="landSlowdownMaxAlt" type="number" data-unit="cm" data-setting="nav_land_slowdown_maxalt" data-setting-multiplier="1" step="1" min="500" max="4000" />
<label for="landSlowdownMaxAlt"><span data-i18n="landSlowdownMaxAlt"></span></label>
<div class="helpicon cf_tip" data-i18n_title="landSlowdownMaxAltHelp"></div>
</div>
<div class="number">
<input id="landMinAltVspd" type="number" data-setting="nav_land_minalt_vspd" data-setting-multiplier="1" step="1" min="50" max="500" />
<input id="landSlowdownMinAlt" type="number" data-unit="cm" data-setting="nav_land_slowdown_minalt" data-setting-multiplier="1" step="1" min="50" max="1000" />
<label for="landSlowdownMinAlt"><span data-i18n="landSlowdownMinAlt"></span></label>
</div>
<div class="number">
<input id="landMinAltVspd" type="number" data-unit="v-cms" data-setting="nav_land_minalt_vspd" data-setting-multiplier="1" step="1" min="50" max="500" />
<label for="landMinAltVspd"><span data-i18n="landMinAltVspd"></span></label>
<div class="helpicon cf_tip" data-i18n_title="landMinAltVspdHelp"></div>
</div>
<div class="number">
<input id="landSlowdownMinAlt" type="number" data-setting="nav_land_slowdown_minalt" data-setting-multiplier="1" step="1" min="50" max="1000" />
<label for="landSlowdownMinAlt"><span data-i18n="landSlowdownMinAlt"></span></label>
</div>
<div class="number">
<input id="emergencyDescentRate" type="number" data-unit="cms" data-setting="nav_emerg_landing_speed" data-setting-multiplier="1" step="1" min="100" max="2000" />
<label for="emergencyDescentRate"><span data-i18n="emergencyDescentRate"></span></label>

View file

@ -18,15 +18,7 @@ TABS.auxiliary.initialize = function (callback) {
}
function get_rc_data() {
if (SERIAL_CONFIG.ports.length == 0) {
MSP.send_message(MSPCodes.MSP_RC, false, false, get_serial_config);
} else {
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
}
}
function get_serial_config() {
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, load_html);
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
}
function load_html() {

View file

@ -53,7 +53,7 @@ TABS.calibration.initialize = function (callback) {
googleAnalytics.sendAppView('Calibration');
}
loadChainer.setChain([
mspHelper.loadStatus,
mspHelper.queryFcStatus,
mspHelper.loadSensorConfig,
mspHelper.loadCalibrationData
]);

View file

@ -14,6 +14,11 @@
<textarea name="commands" i18n_placeholder="cliInputPlaceholder" rows="1" cols="0"></textarea>
</div>
<div class="content_toolbar">
<div class="btn save_btn" style="float: left; padding-left: 15px">
<a class="msc" href="#" i18n="cliMscBtn"></a>
<a class="savecmd" href="#" i18n="cliSaveSettingsBtn"></a>
<a class="exit" href="#" i18n="cliExitBtn"></a>
</div>
<div class="btn save_btn pull-right">
<a class="save" href="#" i18n="cliSaveToFileBtn"></a>
<a class="load" href="#" i18n="cliLoadFromFileBtn"></a>

View file

@ -179,6 +179,18 @@ TABS.cli.initialize = function (callback) {
});
});
$('.tab-cli .exit').click(function() {
self.send(getCliCommand('exit\r', TABS.cli.cliBuffer));
});
$('.tab-cli .savecmd').click(function() {
self.send(getCliCommand('save\r', TABS.cli.cliBuffer));
});
$('.tab-cli .msc').click(function() {
self.send(getCliCommand('msc\r', TABS.cli.cliBuffer));
});
$('.tab-cli .clear').click(function() {
self.outputHistory = "";
$('.tab-cli .window .wrapper').empty();

View file

@ -76,64 +76,6 @@
</div>
</div>
</div>
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationGPS"></div>
</div>
<div class="spacer_box">
<div class="note">
<div class="note_spacer">
<p data-i18n="configurationGPSHelp"></p>
</div>
</div>
<div class="features gps"></div>
<!--feature list generated content-->
<div class="select">
<select id="gps_protocol" class="gps_protocol">
<!-- list generated here -->
</select>
<label for="gps_protocol">
<span data-i18n="configurationGPSProtocol"></span>
</label>
</div>
<div class="select">
<select id="gps_ubx_sbas" class="gps_ubx_sbas">
<!-- list generated here -->
</select>
<label for="gps_ubx_sbas">
<span data-i18n="configurationGPSubxSbas"></span>
</label>
</div>
<div class="number is-hidden">
<input type="number" id="mag_declination" name="mag_declination" step="0.1" min="-180" max="180" />
<label for="mag_declination">
<span data-i18n="configurationMagDeclination"></span>
</label>
</div>
<div class="checkbox">
<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>
</div>
<div class="number">
<input type="number" id="tzOffset" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-1440" max="1440" />
<label for="tzOffset">
<span data-i18n="tzOffset"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="tzOffsetHelp"></div>
</div>
<div class="select">
<select id="tzAutomaticDST" data-setting="tz_automatic_dst"></select>
<label for="tzAutomaticDST">
<span data-i18n="tzAutomaticDST"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="tzAutomaticDSTHelp"></div>
</div>
</div>
</div>
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
@ -290,33 +232,33 @@
</div>
<div class="spacer_box">
<div class="number">
<input type="number" id="cells" name="cells" step="1" min="0" max="12" />
<input type="number" class="batteryProfileHighlight" id="cells" name="cells" step="1" min="0" max="12" />
<label for="cells"><span data-i18n="configurationBatteryCells"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellsHelp"></div>
</div>
<div class="number">
<input type="number" id="celldetectvoltage" name="celldetectvoltage" step="0.01" min="1" max="5" />
<input type="number" class="batteryProfileHighlight" id="celldetectvoltage" name="celldetectvoltage" step="0.01" min="1" max="5" />
<label for="celldetectvoltage"><span data-i18n="configurationBatteryCellDetectVoltage"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellDetectVoltageHelp"></div>
</div>
<div class="number">
<input type="number" id="mincellvoltage" name="mincellvoltage" step="0.01" min="1" max="5" />
<input type="number" class="batteryProfileHighlight" id="mincellvoltage" name="mincellvoltage" step="0.01" min="1" max="5" />
<label for="mincellvoltage"><span data-i18n="configurationBatteryMinimum"></span></label>
</div>
<div class="number">
<input type="number" id="maxcellvoltage" name="maxcellvoltage" step="0.01" min="1" max="5" />
<input type="number" class="batteryProfileHighlight" id="maxcellvoltage" name="maxcellvoltage" step="0.01" min="1" max="5" />
<label for="maxcellvoltage">
<span data-i18n="configurationBatteryMaximum"></span>
</label>
</div>
<div class="number">
<input type="number" id="warningcellvoltage" name="warningcellvoltage" step="0.01" min="1" max="5" />
<input type="number" class="batteryProfileHighlight" id="warningcellvoltage" name="warningcellvoltage" step="0.01" min="1" max="5" />
<label for="warningcellvoltage">
<span data-i18n="configurationBatteryWarning"></span>
</label>
</div>
<div class="select">
<select id="battery_capacity_unit">
<select class="batteryProfileHighlight" id="battery_capacity_unit">
<option value="mAh">mAh</option>
<option value="mWh">mWh</option>
</select>
@ -325,19 +267,19 @@
</label>
</div>
<div class="number">
<input type="number" id="battery_capacity" name="battery_capacity" step="1" min="0" max="4294967296" />
<input type="number" class="batteryProfileHighlight" id="battery_capacity" name="battery_capacity" step="1" min="0" max="4294967296" />
<label for="battery_capacity">
<span data-i18n="configurationBatteryCapacityValue"></span>
</label>
</div>
<div class="number">
<input type="number" id="battery_capacity_warning" name="battery_capacity_warning" step="1" min="0" max="100" />
<input type="number" class="batteryProfileHighlight" id="battery_capacity_warning" name="battery_capacity_warning" step="1" min="0" max="100" />
<label for="battery_capacity_warning">
<span data-i18n="configurationBatteryCapacityWarning"></span>
</label>
</div>
<div class="number">
<input type="number" id="battery_capacity_critical" name="battery_capacity_critical" step="1" min="0" max="100" />
<input type="number" class="batteryProfileHighlight" id="battery_capacity_critical" name="battery_capacity_critical" step="1" min="0" max="100" />
<label for="battery_capacity_critical">
<span data-i18n="configurationBatteryCapacityCritical"></span>
</label>

View file

@ -1,4 +1,4 @@
/*global chrome,GUI,FC_CONFIG,$,mspHelper,googleAnalytics,ADVANCED_CONFIG,VTX_CONFIG,CONFIG,MSPChainerClass*/
/*global chrome,GUI,FC_CONFIG,$,mspHelper,googleAnalytics,ADVANCED_CONFIG,VTX_CONFIG,CONFIG,MSPChainerClass,BOARD_ALIGNMENT,TABS,MISC*/
'use strict';
TABS.configuration = {};
@ -30,15 +30,16 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var loadChainer = new MSPChainerClass();
var loadChain = [
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.loadArmingConfig,
mspHelper.loadLoopTime,
mspHelper.load3dConfig,
mspHelper.loadSensorAlignment,
mspHelper.loadAdvancedConfig,
mspHelper.loadINAVPidConfig,
mspHelper.loadVTXConfig,
mspHelper.loadMixerConfig,
mspHelper.loadBoardAlignment,
mspHelper.loadCurrentMeterConfig,
loadCraftName,
mspHelper.loadMiscV2
];
@ -50,15 +51,15 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var saveChainer = new MSPChainerClass();
var saveChain = [
mspHelper.saveBfConfig,
mspHelper.save3dConfig,
mspHelper.saveSensorAlignment,
mspHelper.saveAccTrim,
mspHelper.saveArmingConfig,
mspHelper.saveLooptimeConfig,
mspHelper.saveAdvancedConfig,
mspHelper.saveINAVPidConfig,
mspHelper.saveVTXConfig,
mspHelper.saveBoardAlignment,
mspHelper.saveCurrentMeterConfig,
saveCraftName,
mspHelper.saveMiscV2,
saveSettings,
@ -133,7 +134,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
});
}
helper.features.updateUI($('.tab-configuration'), BF_CONFIG.features);
helper.features.updateUI($('.tab-configuration'), FEATURES);
// translate to user-selected language
localize();
@ -146,32 +147,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
}
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
// generate GPS
var gpsProtocols = FC.getGpsProtocols();
var gpsSbas = FC.getGpsSbasProviders();
var gps_protocol_e = $('#gps_protocol');
for (i = 0; i < gpsProtocols.length; i++) {
gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>');
}
gps_protocol_e.change(function () {
MISC.gps_type = parseInt($(this).val());
});
gps_protocol_e.val(MISC.gps_type);
var gps_ubx_sbas_e = $('#gps_ubx_sbas');
for (i = 0; i < gpsSbas.length; i++) {
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
}
gps_ubx_sbas_e.change(function () {
MISC.gps_ubx_sbas = parseInt($(this).val());
});
gps_ubx_sbas_e.val(MISC.gps_ubx_sbas);
// VTX
var config_vtx = $('.config-vtx');
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
@ -255,7 +230,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
// fill board alignment
$('input[name="board_align_yaw"]').val((BF_CONFIG.board_align_yaw / 10.0).toFixed(1));
$('input[name="board_align_yaw"]').val((BOARD_ALIGNMENT.yaw / 10.0).toFixed(1));
// fill magnetometer
$('#mag_declination').val(MISC.mag_declination);
@ -270,8 +245,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#voltagescale').val(MISC.vbatscale);
// fill current
$('#currentscale').val(BF_CONFIG.currentscale);
$('#currentoffset').val(BF_CONFIG.currentoffset / 10);
$('#currentscale').val(CURRENT_METER_CONFIG.scale);
$('#currentoffset').val(CURRENT_METER_CONFIG.offset / 10);
// fill battery capacity
$('#battery_capacity').val(MISC.battery_capacity);
@ -351,14 +326,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
craftName = $('input[name="craft_name"]').val();
if (FC.isFeatureEnabled('GPS', features)) {
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
}
googleAnalytics.sendEvent('Setting', 'GPSEnabled', FC.isFeatureEnabled('GPS', features) ? "true" : "false");
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());
googleAnalytics.sendEvent('Board', 'Accelerometer', $('#sensor-acc').children("option:selected").text());
@ -373,13 +340,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
}
}
helper.features.reset();
helper.features.fromUI($('.tab-configuration'));
helper.features.execute(function () {
BF_CONFIG.board_align_yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
BF_CONFIG.currentscale = parseInt($('#currentscale').val());
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
BOARD_ALIGNMENT.yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
CURRENT_METER_CONFIG.scale = parseInt($('#currentscale').val());
CURRENT_METER_CONFIG.offset = Math.round(parseFloat($('#currentoffset').val()) * 10);
saveChainer.execute();
});
});

View file

@ -7,9 +7,8 @@
</div>
<div class="spacer_box">
<div class="number">
<label> <input type="number" name="failsafe_delay" min="0" max="200" /> <span
data-i18n="failsafeDelayItem"></span>
</label>
<input type="number" name="failsafe_delay" data-unit="dsec" data-setting="failsafe_delay" min="0" max="200" />
<label><span data-i18n="failsafeDelayItem"></span></label>
<div class="helpicon cf_tip" data-i18n_title="failsafeDelayHelp"></div>
</div>
<!-- radio buttons -->
@ -25,14 +24,12 @@
</div>
<div class="proceduresettings">
<div class="number">
<label> <input type="number" name="failsafe_throttle" min="0" max="2000" /> <span
data-i18n="failsafeThrottleItem"></span>
</label>
<input type="number" name="failsafe_throttle" data-setting="failsafe_throttle" data-unit="us" min="0" max="2000" />
<label><span data-i18n="failsafeThrottleItem"></span></label>
</div>
<div class="number">
<label> <input type="number" name="failsafe_off_delay" min="0" max="200" /> <span
data-i18n="failsafeOffDelayItem"></span>
</label>
<input type="number" name="failsafe_off_delay" data-setting="failsafe_off_delay" data-unit="dsec" min="0" max="200" />
<label><span data-i18n="failsafeOffDelayItem"></span></label>
<div class="helpicon cf_tip" data-i18n_title="failsafeOffDelayHelp"></div>
</div>
</div>
@ -58,14 +55,13 @@
</div>
<div class="number" id="failsafe_min_distance_elements">
<label> <input class="minimumDistance" type="number" name="failsafe_min_distance" id="failsafe_min_distance" min="0" max="65000" /> <span
data-i18n="failsafeMinDistanceItem"></span>
</label>
<input class="minimumDistance" id="failsafe_min_distance" type="number" data-unit="cm" data-setting="failsafe_min_distance" data-setting-multiplier="1" step="1" min="0" max="65000" />
<label for="failsafe_min_distance"><span data-i18n="failsafeMinDistanceItem"></span></label>
<div class="helpicon cf_tip" data-i18n_title="failsafeMinDistanceHelp"></div>
</div>
<div class="select" id="failsafe_min_distance_procedure_elements">
<select class="minimumDistance" id="failsafe_min_distance_procedure"></select>
<select id="failsafe_min_distance_procedure" class="minimumDistance" data-setting="failsafe_min_distance_procedure"></select>
<label for="failsafe_min_distance_procedure"> <span data-i18n="failsafeMinDistanceProcedureItem"></span></label>
<div class="helpicon cf_tip" data-i18n_title="failsafeMinDistanceProcedureHelp"></div>
</div>

View file

@ -9,174 +9,138 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
googleAnalytics.sendAppView('Failsafe');
}
// Can get rid of this when MSPHelper supports strings (fixed in #7734, awaiting merge)
function load_failssafe_config() {
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_config);
}
function load_config() {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
}
function load_misc() {
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_html);
}
function load_html() {
GUI.load("./tabs/failsafe.html", process_html);
GUI.load("./tabs/failsafe.html", Settings.processHtml(function() {
GUI.simpleBind();
// translate to user-selected language
localize();
// for some odd reason chrome 38+ changes scroll according to the touched select element
// i am guessing this is a bug, since this wasn't happening on 37
// code below is a temporary fix, which we will be able to remove in the future (hopefully)
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
// set stage 2 failsafe procedure
$('input[type="radio"].procedure').change(function () {
var element = $(this),
checked = element.is(':checked'),
id = element.attr('id');
switch (id) {
case 'drop':
if (checked) {
$('input[name="failsafe_throttle"]').prop("disabled", true);
$('input[name="failsafe_off_delay"]').prop("disabled", true);
}
break;
case 'land':
if (checked) {
$('input[name="failsafe_throttle"]').prop("disabled", false);
$('input[name="failsafe_off_delay"]').prop("disabled", false);
}
break;
}
});
// switch (MSPHelper.getSetting('failsafe_procedure')) { // Use once #7734 is merged
switch (FAILSAFE_CONFIG.failsafe_procedure) {
default:
case 0:
element = $('input[id="land"]');
element.prop('checked', true);
element.change();
break;
case 1:
element = $('input[id="drop"]');
element.prop('checked', true);
element.change();
break;
case 2:
element = $('input[id="rth"]');
element.prop('checked', true);
element.change();
break;
case 3:
element = $('input[id="nothing"]');
element.prop('checked', true);
element.change();
break;
}
// Adjust Minimum Distance values when checkbox is checked/unchecked
$('#failsafe_use_minimum_distance').change(function() {
if ($(this).is(':checked')) {
// No default distance added due to conversions
$('#failsafe_min_distance_elements').show();
$('#failsafe_min_distance_procedure_elements').show();
} else {
// If they uncheck it, clear the distance to 0, which disables this feature
$('#failsafe_min_distance').val(0);
$('#failsafe_min_distance_elements').hide();
$('#failsafe_min_distance_procedure_elements').hide();
}
});
// Set initial state of controls according to data
if ( $('#failsafe_min_distance').val() > 0) {
$('#failsafe_use_minimum_distance').prop('checked', true);
$('#failsafe_min_distance_elements').show();
$('#failsafe_min_distance_procedure_elements').show();
} else {
$('#failsafe_use_minimum_distance').prop('checked', false);
$('#failsafe_min_distance_elements').hide();
$('#failsafe_min_distance_procedure_elements').hide();
}
$('a.save').click(function () {
if ($('input[id="land"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 0;
} else if ($('input[id="drop"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 1;
} else if ($('input[id="rth"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 2;
} else if ($('input[id="nothing"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 3;
}
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, savePhaseTwo);
});
GUI.content_ready(callback);
}));
}
load_failssafe_config();
function process_html() {
// translate to user-selected language
localize();
var $failsafeUseMinimumDistanceCheckbox = $('#failsafe_use_minimum_distance');
var $failsafeMinDistanceElements = $('#failsafe_min_distance_elements')
var $failsafeMinDistance = $('#failsafe_min_distance')
var $failsafeMinDistanceProcedureElements = $('#failsafe_min_distance_procedure_elements')
var $failsafeMinDistanceProcedure = $('#failsafe_min_distance_procedure');
// generate labels for assigned aux modes
var element;
// for some odd reason chrome 38+ changes scroll according to the touched select element
// i am guessing this is a bug, since this wasn't happening on 37
// code below is a temporary fix, which we will be able to remove in the future (hopefully)
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
$('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay);
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
// set stage 2 failsafe procedure
$('input[type="radio"].procedure').change(function () {
var element = $(this),
checked = element.is(':checked'),
id = element.attr('id');
switch (id) {
case 'drop':
if (checked) {
$('input[name="failsafe_throttle"]').prop("disabled", true);
$('input[name="failsafe_off_delay"]').prop("disabled", true);
}
break;
case 'land':
if (checked) {
$('input[name="failsafe_throttle"]').prop("disabled", false);
$('input[name="failsafe_off_delay"]').prop("disabled", false);
}
break;
}
function savePhaseTwo() {
Settings.saveInputs().then(function () {
var self = this;
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
setTimeout(function () {
$(self).html(oldText);
}, 2000);
reboot();
});
}
switch (FAILSAFE_CONFIG.failsafe_procedure) {
default:
case 0:
element = $('input[id="land"]');
element.prop('checked', true);
element.change();
break;
case 1:
element = $('input[id="drop"]');
element.prop('checked', true);
element.change();
break;
case 2:
element = $('input[id="rth"]');
element.prop('checked', true);
element.change();
break;
case 3:
element = $('input[id="nothing"]');
element.prop('checked', true);
element.change();
break;
}
// Adjust Minimum Distance values when checkbox is checked/unchecked
$failsafeUseMinimumDistanceCheckbox.change(function() {
if ($(this).is(':checked')) {
// 20 meters seems like a reasonable default for a minimum distance
$failsafeMinDistance.val(2000);
$failsafeMinDistanceElements.show();
$failsafeMinDistanceProcedureElements.show();
} else {
// If they uncheck it, clear the distance to 0, which disables this feature
$failsafeMinDistance.val(0);
$failsafeMinDistanceElements.hide();
$failsafeMinDistanceProcedureElements.hide();
}
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);
});
}
// Set initial state of controls according to data
if (FAILSAFE_CONFIG.failsafe_min_distance > 0) {
$failsafeUseMinimumDistanceCheckbox.prop('checked', true);
$failsafeMinDistanceElements.show();
$failsafeMinDistanceProcedureElements.show();
} else {
$failsafeUseMinimumDistanceCheckbox.prop('checked', false);
$failsafeMinDistanceElements.hide();
$failsafeMinDistanceProcedureElements.hide();
}
// Alternate, minimum distance failsafe procedure
GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure);
$failsafeMinDistanceProcedure.val(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
$failsafeMinDistanceProcedure.change(function () {
FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val();
});
$('a.save').click(function () {
FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val());
FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val());
FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val());
FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val());
if ($('input[id="land"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 0;
} else if ($('input[id="drop"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 1;
} else if ($('input[id="rth"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 2;
} else if ($('input[id="nothing"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 3;
}
function save_failssafe_config() {
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_bf_config);
}
function save_bf_config() {
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
}
function save_to_eeprom() {
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
}
function reboot() {
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_failsafe a'));
}
save_failssafe_config();
});
GUI.content_ready(callback);
function reinitialize() {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect($('.tab_failsafe a'));
}
};

View file

@ -44,6 +44,7 @@ TABS.firmware_flasher.initialize = function (callback) {
}
return {
raw_target: match[2],
target: match[2].replace("_", " "),
format: match[3],
};
@ -60,7 +61,7 @@ TABS.firmware_flasher.initialize = function (callback) {
var target = $(this);
//alert("Comparing " + searchText + " with " + target.text());
if (searchText.length > 0 && i !== 0) {
if (target.text().toLowerCase().includes(searchText)) {
if (target.text().toLowerCase().includes(searchText) || target.val().toLowerCase().includes(searchText)) {
target.show();
} else {
target.hide();
@ -130,6 +131,7 @@ TABS.firmware_flasher.initialize = function (callback) {
"version" : release.tag_name,
"url" : asset.browser_download_url,
"file" : asset.name,
"raw_target": result.raw_target,
"target" : result.target,
"date" : formattedDate,
"notes" : release.body,
@ -147,7 +149,8 @@ TABS.firmware_flasher.initialize = function (callback) {
if($.inArray(target, selectTargets) == -1) {
selectTargets.push(target);
var select_e =
$("<option value='{0}'>{0}</option>".format(
$("<option value='{0}'>{1}</option>".format(
descriptor.raw_target,
descriptor.target
)).data('summary', descriptor);
boards_e.append(select_e);
@ -165,7 +168,7 @@ TABS.firmware_flasher.initialize = function (callback) {
$('select[name="board"]').change(function() {
$("a.load_remote_file").addClass('disabled');
var target = $(this).val();
var target = $(this).children("option:selected").text();
if (!GUI.connect_lock) {
$('.progress').val(0).removeClass('valid invalid');

View file

@ -1,8 +1,78 @@
<div class="tab-gps">
<div class="tab-gps toolbar_fixed_bottom">
<div class="content_wrapper">
<div class="tab_title" data-i18n="tabGPS">GPS</div>
<div class="cf_column fourth">
<div class="cf_column third_left">
<div class="spacer_right">
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationGPS"></div>
</div>
<div class="spacer_box">
<div class="note">
<div class="note_spacer">
<p data-i18n="configurationGPSHelp"></p>
</div>
</div>
<div class="checkbox">
<input type="checkbox" data-bit="7" class="feature toggle" name="GPS" title="GPS"
id="feature-7">
<label for="feature-7">
<span data-i18n="featureGPS"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="featureGPSTip"></div>
</div>
<div class="select">
<select id="gps_protocol" class="gps_protocol">
<!-- list generated here -->
</select>
<label for="gps_protocol">
<span data-i18n="configurationGPSProtocol"></span>
</label>
</div>
<div class="select">
<select id="gps_ubx_sbas" class="gps_ubx_sbas">
<!-- list generated here -->
</select>
<label for="gps_ubx_sbas">
<span data-i18n="configurationGPSubxSbas"></span>
</label>
</div>
<div class="number is-hidden">
<input type="number" id="mag_declination" name="mag_declination" step="0.1" min="-180"
max="180" />
<label for="mag_declination">
<span data-i18n="configurationMagDeclination"></span>
</label>
</div>
<div class="checkbox">
<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>
</div>
<div class="number">
<input type="number" id="tzOffset" data-setting="tz_offset" data-setting-multiplier="1"
step="1" min="-1440" max="1440" />
<label for="tzOffset">
<span data-i18n="tzOffset"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="tzOffsetHelp"></div>
</div>
<div class="select">
<select id="tzAutomaticDST" data-setting="tz_automatic_dst"></select>
<label for="tzAutomaticDST">
<span data-i18n="tzAutomaticDST"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="tzAutomaticDSTHelp"></div>
</div>
</div>
</div>
<div class="gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="gpsHead"></div>
@ -80,18 +150,23 @@
</div>
</div>
<div class="cf_column threefourth_left">
<div class="cf_column twothird">
<div class="gui_box grey gps_map">
<div class="gui_box_titlebar" style="margin-bottom: 0;">
<div class="spacer_box_title" data-i18n="gpsMapHead"></div>
</div>
<div id="loadmap">
<div style="height:100%" id="gps-map">
<button class="map-button" id="center_button" data-i18n="gps_map_center"></button>
<button class="map-button" id="center_button" data-i18n="gps_map_center"></button>
</div>
</div>
</div>
</div>
</div>
</div>
</div>
</div>
<div class="content_toolbar">
<div class="btn save_btn">
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
</div>
</div>
</div>

View file

@ -1,3 +1,4 @@
/*global $,MSPChainerClass,googleAnalytics,mspHelper,MSPCodes,GUI,chrome,MSP,TABS,Settings,helper,ol*/
'use strict';
TABS.gps = {};
@ -8,11 +9,48 @@ TABS.gps.initialize = function (callback) {
googleAnalytics.sendAppView('GPS');
}
function load_html() {
GUI.load("./tabs/gps.html", process_html);
var loadChainer = new MSPChainerClass();
var loadChain = [
mspHelper.loadFeatures,
mspHelper.loadMiscV2
];
loadChainer.setChain(loadChain);
loadChainer.setExitPoint(load_html);
loadChainer.execute();
var saveChainer = new MSPChainerClass();
var saveChain = [
mspHelper.saveMiscV2,
saveSettings,
mspHelper.saveToEeprom
];
function saveSettings(onComplete) {
Settings.saveInputs().then(onComplete);
}
load_html();
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, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect($('.tab_gps a'));
});
});
}
function load_html() {
GUI.load("./tabs/gps.html", Settings.processHtml(process_html));
}
let cursorInitialized = false;
let iconStyle;
@ -23,6 +61,36 @@ TABS.gps.initialize = function (callback) {
function process_html() {
localize();
var features = FC.getFeatures();
helper.features.updateUI($('.tab-gps'), FEATURES);
// generate GPS
var gpsProtocols = FC.getGpsProtocols();
var gpsSbas = FC.getGpsSbasProviders();
var gps_protocol_e = $('#gps_protocol');
for (i = 0; i < gpsProtocols.length; i++) {
gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>');
}
gps_protocol_e.change(function () {
MISC.gps_type = parseInt($(this).val());
});
gps_protocol_e.val(MISC.gps_type);
var gps_ubx_sbas_e = $('#gps_ubx_sbas');
for (i = 0; i < gpsSbas.length; i++) {
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
}
gps_ubx_sbas_e.change(function () {
MISC.gps_ubx_sbas = parseInt($(this).val());
});
gps_ubx_sbas_e.val(MISC.gps_ubx_sbas);
let mapView = new ol.View({
center: ol.proj.fromLonLat([0, 0]),
zoom: 15
@ -36,20 +104,20 @@ TABS.gps.initialize = function (callback) {
imagerySet: 'AerialWithLabels',
maxZoom: 19
});
} else if ( globalSettings.mapProviderType == 'mapproxy' ) {
mapLayer = new ol.source.TileWMS({
url: globalSettings.proxyURL,
params: {'LAYERS':globalSettings.proxyLayer}
})
} else if (globalSettings.mapProviderType == 'mapproxy') {
mapLayer = new ol.source.TileWMS({
url: globalSettings.proxyURL,
params: { 'LAYERS': globalSettings.proxyLayer }
})
} else {
mapLayer = new ol.source.OSM();
}
$("#center_button").click(function(){
let lat = GPS_DATA.lat / 10000000;
let lon = GPS_DATA.lon / 10000000;
let center = ol.proj.fromLonLat([lon, lat]);
mapView.setCenter(center);
$("#center_button").click(function () {
let lat = GPS_DATA.lat / 10000000;
let lon = GPS_DATA.lon / 10000000;
let center = ol.proj.fromLonLat([lon, lat]);
mapView.setCenter(center);
});
mapHandler = new ol.Map({
@ -144,7 +212,7 @@ TABS.gps.initialize = function (callback) {
});
mapHandler.addLayer(currentPositionLayer);
mapView.setCenter(center);
mapView.setZoom(14);
}
@ -172,6 +240,29 @@ TABS.gps.initialize = function (callback) {
get_raw_gps_data();
});
$('a.save').on('click', function () {
if (FC.isFeatureEnabled('GPS', features)) {
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
}
googleAnalytics.sendEvent('Setting', 'GPSEnabled', FC.isFeatureEnabled('GPS', features) ? "true" : "false");
for (var i = 0; i < features.length; i++) {
var featureName = features[i].name;
if (FC.isFeatureEnabled(featureName, features)) {
googleAnalytics.sendEvent('Setting', 'Feature', featureName);
}
}
helper.features.reset();
helper.features.fromUI($('.tab-gps'));
helper.features.execute(function () {
saveChainer.execute();
});
});
GUI.content_ready(callback);
}

View file

@ -65,6 +65,7 @@
<option value="function-s" class="extra_functions20">RSSI</option>
<option value="function-g" class="extra_functions20">GPS</option>
<option value="function-r" class="">Ring</option>
<option value="function-h" class="channel_info">Channel</option>
</select>
</div>
@ -104,6 +105,10 @@
<label> <span>Indicator</span></label>
</div>
</div>
<div class="channel_info">
<span class="color_section">Select Channel from color list</span>
</div>
<div class="mode_colors">
<div class="section">Mode colors</div>

View file

@ -11,15 +11,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
var selectedColorIndex = null;
var selectedModeColor = null;
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
TABS.led_strip.functions = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b'];
TABS.led_strip.baseFuncs = ['c', 'f', 'a', 'b', 'g', 'r'];
TABS.led_strip.overlays = ['t', 's', 'i', 'w'];
} else {
TABS.led_strip.functions = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l', 'o', 'n'];
TABS.led_strip.baseFuncs = ['c', 'f', 'a', 'l', 's', 'g', 'r'];
TABS.led_strip.overlays = ['t', 'o', 'b', 'n', 'i', 'w'];
}
TABS.led_strip.functions = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l', 'o', 'n'];
TABS.led_strip.baseFuncs = ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'];
TABS.led_strip.overlays = ['t', 'o', 'b', 'n', 'i', 'w'];
TABS.led_strip.wireMode = false;
@ -37,16 +31,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
}
function load_led_mode_colors() {
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
MSP.send_message(MSPCodes.MSP_LED_STRIP_MODECOLOR, false, false, load_html);
else
load_html();
MSP.send_message(MSPCodes.MSP_LED_STRIP_MODECOLOR, false, false, load_html);
}
function load_html() {
GUI.load("./tabs/led_strip.html", process_html);
}
@ -74,10 +61,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
var theHTML = [];
var theHTMLlength = 0;
for (var i = 0; i < 256; i++) {
if (semver.lte(CONFIG.apiVersion, "1.19.0"))
theHTML[theHTMLlength++] = ('<div class="gPoint"><div class="indicators"><span class="north"></span><span class="south"></span><span class="west"></span><span class="east"></span><span class="up">U</span><span class="down">D</span></div><span class="wire"></span><span class="overlay-t"> </span><span class="overlay-s"> </span><span class="overlay-w"> </span><span class="overlay-i"> </span><span class="overlay-color"> </span></div>');
else
theHTML[theHTMLlength++] = ('<div class="gPoint"><div class="indicators"><span class="north"></span><span class="south"></span><span class="west"></span><span class="east"></span><span class="up">U</span><span class="down">D</span></div><span class="wire"></span><span class="overlay-t"> </span><span class="overlay-o"> </span><span class="overlay-b"> </span><span class="overlay-n"> </span><span class="overlay-w"> </span><span class="overlay-i"> </span><span class="overlay-color"> </span></div>');
theHTML[theHTMLlength++] = ('<div class="gPoint"><div class="indicators"><span class="north"></span><span class="south"></span><span class="west"></span><span class="east"></span><span class="up">U</span><span class="down">D</span></div><span class="wire"></span><span class="overlay-t"> </span><span class="overlay-o"> </span><span class="overlay-b"> </span><span class="overlay-n"> </span><span class="overlay-w"> </span><span class="overlay-i"> </span><span class="overlay-color"> </span></div>');
}
$('.mainGrid').html(theHTML.join(''));
@ -549,10 +533,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
}
function send_led_strip_mode_colors() {
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
mspHelper.sendLedStripModeColors(save_to_eeprom);
else
save_to_eeprom();
mspHelper.sendLedStripModeColors(save_to_eeprom);
}
function save_to_eeprom() {
@ -674,20 +655,18 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
// refresh mode color buttons
function setModeBackgroundColor(element) {
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
element.find('[class*="mode_color"]').each(function() {
var m = 0;
var d = 0;
element.find('[class*="mode_color"]').each(function() {
var m = 0;
var d = 0;
var match = $(this).attr("class").match(/(^|\s)mode_color-([0-9]+)-([0-9]+)(\s|$)/);
if (match) {
m = Number(match[2]);
d = Number(match[3]);
$(this).css('background-color', HsvToColor(LED_COLORS[getModeColor(m, d)]));
}
});
}
}
var match = $(this).attr("class").match(/(^|\s)mode_color-([0-9]+)-([0-9]+)(\s|$)/);
if (match) {
m = Number(match[2]);
d = Number(match[3]);
$(this).css('background-color', HsvToColor(LED_COLORS[getModeColor(m, d)]));
}
});
}
function setBackgroundColor(element) {
if (element.is('[class*="color"]')) {
@ -713,42 +692,29 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
}
function areOverlaysActive(activeFunction) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
switch (activeFunction) {
case "function-c":
case "function-a":
case "function-f":
case "function-g":
return true;
break;
}
} else {
switch (activeFunction) {
case "":
case "function-c":
case "function-a":
case "function-f":
case "function-s":
case "function-l":
case "function-r":
case "function-o":
case "function-g":
return true;
break;
}
switch (activeFunction) {
case "":
case "function-c":
case "function-a":
case "function-f":
case "function-s":
case "function-l":
case "function-r":
case "function-o":
case "function-g":
return true;
break;
}
return false;
}
function areBlinkersActive(activeFunction) {
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
switch (activeFunction) {
case "function-c":
case "function-a":
case "function-f":
return true;
break;
}
switch (activeFunction) {
case "function-c":
case "function-a":
case "function-f":
return true;
break;
}
return false;
}
@ -758,13 +724,10 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
case "function-l":
case "function-s":
case "function-g":
return false;
break;
case "function-r":
case "function-b":
if (semver.lt(CONFIG.apiVersion, "1.20.0"))
return false;
break;
return false;
break;
default:
return true;
break;
@ -776,29 +739,19 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
var activeFunction = $('select.functionSelect').val();
$('select.functionSelect').addClass(activeFunction);
if (semver.lte(CONFIG.apiVersion, "1.18.0")) {
// <= 18
// Hide GPS (Func)
// Hide RSSI (O/L), Blink (Func)
// Hide Battery, RSSI (Func), Larson (O/L), Blink (O/L), Landing (O/L)
$(".extra_functions20").hide();
$(".mode_colors").hide();
} else {
// >= 20
// Show GPS (Func)
// Hide RSSI (O/L), Blink (Func)
// Show Battery, RSSI (Func), Larson (O/L), Blink (O/L), Landing (O/L)
$(".extra_functions20").show();
$(".mode_colors").show();
}
// >= 20
// Show GPS (Func)
// Hide RSSI (O/L), Blink (Func)
// Show Battery, RSSI (Func), Larson (O/L), Blink (O/L), Landing (O/L)
$(".extra_functions20").show();
$(".mode_colors").show();
// set color modifiers (check-boxes) visibility
$('.overlays').hide();
$('.modifiers').hide();
$('.blinkers').hide();
$('.warningOverlay').hide();
$('.channel_info').hide();
if (areOverlaysActive(activeFunction))
$('.overlays').show();
@ -812,67 +765,53 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
if (isWarningActive(activeFunction))
$('.warningOverlay').show();
$('.mode_colors').hide();
// set mode colors visibility
// set directions visibility
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
switch (activeFunction) {
case "function-r":
$('.indicatorOverlay').hide();
$('.directions').hide();
break;
default:
$('.indicatorOverlay').show();
$('.directions').show();
break;
}
if (activeFunction == "function-f") {
$('.mode_colors').show();
}
$('.mode_colors').hide();
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
// set mode colors visibility
// set special colors visibility
$('.special_colors').show();
$('.mode_color-6-0').hide();
$('.mode_color-6-1').hide();
$('.mode_color-6-2').hide();
$('.mode_color-6-3').hide();
$('.mode_color-6-4').hide();
$('.mode_color-6-5').hide();
$('.mode_color-6-6').hide();
$('.mode_color-6-7').hide();
if (semver.gte(CONFIG.apiVersion, "1.20.0"))
if (activeFunction == "function-f")
$('.mode_colors').show();
// set special colors visibility
$('.special_colors').show();
$('.mode_color-6-0').hide();
$('.mode_color-6-1').hide();
$('.mode_color-6-2').hide();
$('.mode_color-6-3').hide();
$('.mode_color-6-4').hide();
$('.mode_color-6-5').hide();
$('.mode_color-6-6').hide();
$('.mode_color-6-7').hide();
switch (activeFunction) {
case "": // none
case "function-f": // Modes & Orientation
case "function-l": // Battery
// $('.mode_color-6-3').show(); // background
$('.special_colors').hide();
break;
case "function-g": // GPS
$('.mode_color-6-5').show(); // no sats
$('.mode_color-6-6').show(); // no lock
$('.mode_color-6-7').show(); // locked
// $('.mode_color-6-3').show(); // background
break;
case "function-b": // Blink
$('.mode_color-6-4').show(); // blink background
break;
case "function-a": // Arm state
$('.mode_color-6-0').show(); // disarmed
$('.mode_color-6-1').show(); // armed
break;
case "function-r": // Ring
default:
$('.special_colors').hide();
switch (activeFunction) {
case "": // none
case "function-f": // Modes & Orientation
case "function-l": // Battery
// $('.mode_color-6-3').show(); // background
$('.special_colors').hide();
break;
}
case "function-g": // GPS
$('.mode_color-6-5').show(); // no sats
$('.mode_color-6-6').show(); // no lock
$('.mode_color-6-7').show(); // locked
// $('.mode_color-6-3').show(); // background
break;
case "function-b": // Blink
$('.mode_color-6-4').show(); // blink background
break;
case "function-a": // Arm state
$('.mode_color-6-0').show(); // disarmed
$('.mode_color-6-1').show(); // armed
break;
case "function-h": // Channel
$('.special_colors').hide();
$('.channel_info').show();
break;
case "function-r": // Ring
default:
$('.special_colors').hide();
break;
}
}
@ -903,30 +842,19 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
}
function unselectOverlays(letter) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
if (letter == 'b' || letter == 'r') {
unselectOverlay(letter, 'i');
}
if (letter == 'b' || letter == 'r' || letter == 'l' || letter == 'g') {
unselectOverlay(letter, 'w');
unselectOverlay(letter, 't');
unselectOverlay(letter, 's');
}
} else {
// MSP 1.20
if (letter == 'r' || letter == '') {
unselectOverlay(letter, 'o');
unselectOverlay(letter, 'b');
unselectOverlay(letter, 'n');
unselectOverlay(letter, 't');
}
if (letter == 'l' || letter == 'g' || letter == 's') {
unselectOverlay(letter, 'w');
unselectOverlay(letter, 't');
unselectOverlay(letter, 'o');
unselectOverlay(letter, 'b');
unselectOverlay(letter, 'n');
}
// MSP 1.20
if (letter == 'r' || letter == '') {
unselectOverlay(letter, 'o');
unselectOverlay(letter, 'b');
unselectOverlay(letter, 'n');
unselectOverlay(letter, 't');
}
if (letter == 'l' || letter == 'g' || letter == 's') {
unselectOverlay(letter, 'w');
unselectOverlay(letter, 't');
unselectOverlay(letter, 'o');
unselectOverlay(letter, 'b');
unselectOverlay(letter, 'n');
}
}

View file

@ -1543,11 +1543,7 @@ TABS.mission_control.initialize = function (callback) {
// * @param {Object=} opt_options Control options.
// */
app.PlannerMultiMissionControl = function (opt_options) {
let versionCheck = true;
if (CONFIG !== undefined && !semver.gte(CONFIG.flightControllerVersion, "4.0.0")) {
versionCheck = false;
}
var options = opt_options || {};
var button = document.createElement('button');
@ -1555,9 +1551,7 @@ TABS.mission_control.initialize = function (callback) {
button.style = 'background: url(\'../images/icons/cf_icon_multimission_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
var handleShowSettings = function () {
if (versionCheck) {
$('#missionPlannerMultiMission').fadeIn(300);
}
$('#missionPlannerMultiMission').fadeIn(300);
};
button.addEventListener('click', handleShowSettings, false);
@ -1566,7 +1560,7 @@ TABS.mission_control.initialize = function (callback) {
var element = document.createElement('div');
element.className = 'mission-control-multimission ol-unselectable ol-control';
element.appendChild(button);
element.title = versionCheck ? 'MP MultiMission' : 'Unavailable';
element.title = 'MP MultiMission';
ol.control.Control.call(this, {
element: element,

View file

@ -15,6 +15,11 @@
<span data-i18n="platformType"></span>
</label>
</div>
<div class="checkbox">
<input id="motor_direction_inverted" type="checkbox" class="toggle" data-setting="motor_direction_inverted" />
<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>
</div>
</div>
</div>
@ -31,7 +36,9 @@
<div class="half" style="width: calc(50% - 10px); margin-left: 10px;">
<select id="mixer-preset"></select>
</div>
<div class="mixer-load-button">
<div id="needToUpdateMixerMessage" class="is-hidden" data-i18n="mixerNotLoaded"></div>
<div class="btn default_btn narrow green is-hidden">
<a id="mixer-wizard" href="#" data-i18n="mixerWizard"></a>
</div>
@ -41,6 +48,9 @@
<div class="btn default_btn narrow">
<a id="load-mixer-button" href="#" data-i18n="mixerLoadPresetRules"></a>
</div>
<div class="btn default_btn narrow is-hidden">
<a id="refresh-mixer-button" href="#" data-i18n="mixerRefreshCurrentRules"></a>
</div>
</div>
</div>
</div>

View file

@ -9,6 +9,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
saveChainer = new MSPChainerClass(),
currentPlatform,
currentMixerPreset,
loadedMixerPresetID,
$servoMixTable,
$servoMixTableBody,
$motorMixTable,
@ -36,10 +37,15 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
mspHelper.saveMixerConfig,
mspHelper.sendServoMixer,
mspHelper.sendMotorMixer,
saveSettings,
mspHelper.saveToEeprom
]);
saveChainer.setExitPoint(reboot);
function saveSettings(onComplete) {
Settings.saveInputs().then(onComplete);
}
function reboot() {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
@ -56,7 +62,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
}
function loadHtml() {
GUI.load("./tabs/mixer.html", processHtml);
GUI.load("./tabs/mixer.html", Settings.processHtml(processHtml));
}
function renderOutputTable() {
@ -86,6 +92,165 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
for (let i = 1; i <= OUTPUT_MAPPING.getOutputCount(); i++) {
$('#function-' + i).html(outputMap[i - 1]);
}
renderServoOutputImage(outputMap);
}
function renderServoOutputImage(outputMap) {
let mixerPreview = $('.mixerPreview');
mixerPreview.find('.outputImageNumber').remove();
$(".mix-rule-servo").each(function() {
$(this).css("background-color", "");
$(this).css("font-weight", "");
$(this).css("color", "");
});
if (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE) {
if (outputMap != null && currentMixerPreset.hasOwnProperty('imageOutputsNumbers')) {
let outputPad = 1;
let outputArea = null;
let inputBoxes = null;
let surfaceSet = {
aileron: false,
elevator: false,
rudder: false,
};
let motors = [];
let servoRules = SERVO_RULES;
for (let omIndex of outputMap) {
if (omIndex != '-') {
omIndex = omIndex.split(' ');
if (omIndex[0] == "Motor") {
motors.push(outputPad);
} else {
let servo = servoRules.getServoMixRuleFromTarget(omIndex[1]);
let divID = "servoPreview" + omIndex[1];
switch (parseInt(servo.getInput())) {
case INPUT_STABILIZED_PITCH:
case INPUT_RC_PITCH:
outputArea = getOutputImageArea(currentMixerPreset.imageOutputsNumbers, INPUT_STABILIZED_PITCH, surfaceSet.elevator);
if (outputArea != null) {
mixerPreview.append('<div id="' + divID + '" class="outputImageNumber">S' + outputPad + '</div>');
$("#"+divID).css("top", outputArea.top + "px");
$("#"+divID).css("left", outputArea.left + "px");
$("#"+divID).css("border-color", outputArea.colour);
inputBoxes = getServoNumberInput(servo.getTarget());
if (inputBoxes.length > 0) {
$.each(inputBoxes, function() {
$(this).css("background-color", outputArea.colour);
$(this).css("font-weight", "bold");
$(this).css("color", "#FFFFFF");
});
}
surfaceSet.elevator = true;
}
break;
case INPUT_STABILIZED_ROLL:
case INPUT_RC_ROLL:
outputArea = getOutputImageArea(currentMixerPreset.imageOutputsNumbers, INPUT_STABILIZED_ROLL, surfaceSet.aileron);
if (outputArea != null) {
mixerPreview.append('<div id="' + divID + '" class="outputImageNumber">S' + outputPad + '</div>');
$("#"+divID).css("top", outputArea.top + "px");
$("#"+divID).css("left", outputArea.left + "px");
$("#"+divID).css("border-color", outputArea.colour);
inputBoxes = getServoNumberInput(servo.getTarget());
if (inputBoxes.length > 0) {
$.each(inputBoxes, function() {
$(this).css("background-color", outputArea.colour);
$(this).css("font-weight", "bold");
$(this).css("color", "#FFFFFF");
});
}
surfaceSet.aileron = true;
}
break;
case INPUT_STABILIZED_YAW:
case INPUT_RC_YAW:
outputArea = getOutputImageArea(currentMixerPreset.imageOutputsNumbers, INPUT_STABILIZED_YAW, surfaceSet.rudder);
if (outputArea != null) {
mixerPreview.append('<div id="' + divID + '" class="outputImageNumber">S' + outputPad + '</div>');
$("#"+divID).css("top", outputArea.top + "px");
$("#"+divID).css("left", outputArea.left + "px");
$("#"+divID).css("border-color", outputArea.colour);
inputBoxes = getServoNumberInput(servo.getTarget());
if (inputBoxes.length > 0) {
$.each(inputBoxes, function() {
$(this).css("background-color", outputArea.colour);
$(this).css("font-weight", "bold");
$(this).css("color", "#FFFFFF");
});
}
surfaceSet.rudder = true;
}
break;
}
}
}
outputPad++;
}
if (motors.length > 0) {
mixerPreview.append('<div id="motorsPreview" class="outputImageNumber isMotor">S' + motors.join('/') + '</div>');
outputArea = getOutputImageArea(currentMixerPreset.imageOutputsNumbers, INPUT_STABILIZED_THROTTLE, false);
if (outputArea != null) {
$("#motorsPreview").css("top", outputArea.top + "px");
$("#motorsPreview").css("left", outputArea.left + "px");
$("#motorsPreview").css("border-color", outputArea.colour);
}
}
}
}
}
function getOutputImageArea(outputImageAreas, input, secondSurface) {
let returnArea = null;
let firstAileronFound = false;
let firstRuddervatorFound = false;
for (let area of outputImageAreas) {
if (area.input == input) {
if ( input === INPUT_STABILIZED_THROTTLE
|| (input === INPUT_STABILIZED_YAW && !secondSurface)
|| ((input === INPUT_STABILIZED_ROLL && !secondSurface) || (input === INPUT_STABILIZED_ROLL && secondSurface && firstAileronFound))
|| ((input === INPUT_STABILIZED_PITCH && !secondSurface) || (input === INPUT_STABILIZED_PITCH && secondSurface && firstRuddervatorFound))
) {
returnArea = area;
break;
} else if (input === INPUT_STABILIZED_ROLL) {
firstAileronFound = true;
} else if (input === INPUT_STABILIZED_PITCH) {
firstRuddervatorFound = true;
}
}
}
return returnArea;
}
function getServoNumberInput(target) {
let servoInputs = [];
$(".mix-rule-servo").each(function() {
if ($(this).val() == target) {
servoInputs.push($(this));
}
});
return servoInputs;
}
function renderServoMixRules() {
@ -131,6 +296,8 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
$row.find(".mix-rule-input").val(servoRule.getInput()).change(function () {
servoRule.setInput($(this).val());
updateFixedValueVisibility($row, $(this));
renderOutputMapping();
});
$row.find(".mix-rule-servo").val(servoRule.getTarget()).change(function () {
@ -381,11 +548,23 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
$wizardButton.parent().addClass("is-hidden");
}
if (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE && currentMixerPreset.id != loadedMixerPresetID) {
$("#needToUpdateMixerMessage").removeClass("is-hidden");
} else {
$("#needToUpdateMixerMessage").addClass("is-hidden");
}
updateRefreshButtonStatus();
$('.mixerPreview img').attr('src', './resources/motor_order/'
+ currentMixerPreset.image + '.svg');
renderServoOutputImage();
});
if (MIXER_CONFIG.appliedMixerPreset > -1) {
loadedMixerPresetID = MIXER_CONFIG.appliedMixerPreset;
$("#needToUpdateMixerMessage").addClass("is-hidden");
$mixerPreset.val(MIXER_CONFIG.appliedMixerPreset).change();
} else {
$mixerPreset.change();
@ -402,6 +581,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
});
$('#execute-button').click(function () {
loadedMixerPresetID = currentMixerPreset.id;
helper.mixer.loadServoRules(currentMixerPreset);
helper.mixer.loadMotorRules(currentMixerPreset);
renderServoMixRules();
@ -412,12 +592,28 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
});
$('#load-mixer-button').click(function () {
if (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE) {
$("#needToUpdateMixerMessage").addClass("is-hidden");
}
loadedMixerPresetID = currentMixerPreset.id;
helper.mixer.loadServoRules(currentMixerPreset);
helper.mixer.loadMotorRules(currentMixerPreset);
MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
renderServoMixRules();
renderMotorMixRules();
renderOutputMapping();
updateRefreshButtonStatus();
});
$('#refresh-mixer-button').click(function () {
currentMixerPreset = helper.mixer.getById(loadedMixerPresetID);
MIXER_CONFIG.platformType = currentMixerPreset.platform;
currentPlatform = helper.platform.getById(MIXER_CONFIG.platformType);
$platformSelect.val(MIXER_CONFIG.platformType).change();
$mixerPreset.val(loadedMixerPresetID).change();
renderServoMixRules();
renderMotorMixRules();
renderOutputMapping();
});
$servoMixTableBody.on('click', "[data-role='role-servo-delete']", function (event) {
@ -438,7 +634,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
$("[data-role='role-servo-add']").click(function () {
if (SERVO_RULES.hasFreeSlots()) {
SERVO_RULES.put(new ServoMixRule(0, 0, 100, 0));
SERVO_RULES.put(new ServoMixRule(SERVO_RULES.getNextUnusedIndex(), 0, 100, 0));
renderServoMixRules();
renderOutputMapping();
}
@ -473,6 +669,17 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
GUI.content_ready(callback);
}
function updateRefreshButtonStatus() {
if (
(currentMixerPreset.id != loadedMixerPresetID && helper.mixer.getById(loadedMixerPresetID).platform == PLATFORM_AIRPLANE) ||
(currentMixerPreset.id == loadedMixerPresetID && currentMixerPreset.platform == PLATFORM_AIRPLANE)
) {
$("#refresh-mixer-button").parent().removeClass("is-hidden");
} else {
$("#refresh-mixer-button").parent().addClass("is-hidden");
}
}
function getLogicConditionsStatus() {
mspHelper.loadLogicConditionsStatus(onStatusPullDone);
}

View file

@ -25,11 +25,12 @@
</div>
</div>
<div class="require-blackbox-supported">
<div class="gui_box grey require-blackbox-config-supported">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="blackboxConfiguration"></div>
</div>
<div class="spacer_box config-section">
<div class="leftWrapper">
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="blackboxConfiguration"></div>
</div>
<div class="spacer_box">
<div class="checkbox">
<input checked type="checkbox" data-bit="19" class="feature toggle" name="BLACKBOX" title="BLACKBOX" id="feature-19-2">
<label for="feature-19-2">
@ -46,24 +47,31 @@
</select>
<span>Portion of flight loop iterations to log (logging rate)</span>
</div>
<div class="line">
<a href="#" class="save-settings regular-button" data-i18n="blackboxButtonSave"></a>
</div>
</div>
</div>
<div class="gui_box grey">
<div class="gui_box_titlebar" align="left">
<div class="spacer_box_title">
Outboard serial logging device
<div class="rightWrapper">
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="blackboxFields"></div>
</div>
</div>
<div class="spacer_box">
<p data-i18n="serialLoggingSupportedNote"></p>
<div id="blackBoxFlagsDiv" class="spacer_box config-section">
</div>
</div>
</div>
<div class="gui_box grey">
<div class="gui_box_titlebar" align="left">
<div class="spacer_box_title">
Outboard serial logging device
</div>
</div>
<div class="spacer_box">
<p data-i18n="serialLoggingSupportedNote"></p>
</div>
</div>
<div class="gui_box grey require-dataflash-supported">
<div class="gui_box grey require-dataflash-supported">
<div class="gui_box_titlebar" align="left">
<div class="spacer_box_title">
Onboard dataflash chip
@ -122,35 +130,40 @@
<p class="require-dataflash-not-present" data-i18n="dataflashNotPresentNote"></p>
<p class="require-dataflash-unsupported" data-i18n="dataflashFirmwareUpgradeRequired"></p>
</div>
</div>
<div class="require-sdcard-supported">
<div class="gui_box grey">
<div class="gui_box_titlebar" align="left">
<div class="spacer_box_title">
Onboard SD card
</div>
</div>
<div class="require-sdcard-supported">
<div class="gui_box grey">
<div class="gui_box_titlebar" align="left">
<div class="spacer_box_title">
Onboard SD card
</div>
<div class="spacer_box">
<div class="sdcard">
<div class="sdcard-icon"></div>
<div class="sdcard-status"></div>
</div>
</div>
<div class="spacer_box">
<div class="sdcard">
<div class="sdcard-icon"></div>
<div class="sdcard-status"></div>
</div>
<p data-i18n="sdcardNote"></p>
<p data-i18n="sdcardNote"></p>
<div class="require-sdcard-ready">
<ul class="sdcard-contents">
<li class="sdcard-other">
<div class="legend"></div>
</li>
<li class="sdcard-free">
<div class="legend"></div>
</li>
</ul>
</div>
<div class="require-sdcard-ready">
<ul class="sdcard-contents">
<li class="sdcard-other">
<div class="legend"></div>
</li>
<li class="sdcard-free">
<div class="legend"></div>
</li>
</ul>
</div>
</div>
</div>
</div>
</div>
</div>
<div class="content_toolbar">
<div class="btn save_btn">
<a href="#" class="save-settings regular-button" data-i18n="blackboxButtonSave"></a>
</div>
</div>
</div>

View file

@ -1,4 +1,4 @@
/*global $,MSP,MSPCodes,BF_CONFIG,TABS,GUI,CONFIGURATOR,helper,mspHelper,nwdialog,SDCARD,chrome*/
/*global $,MSP,MSPCodes,TABS,GUI,CONFIGURATOR,helper,mspHelper,nwdialog,SDCARD,chrome*/
'use strict';
var
@ -11,13 +11,26 @@ TABS.onboard_logging.initialize = function (callback) {
let
saveCancelled, eraseCancelled;
//Add future blackbox values here and in messages.json, the checkbox are drawn by js
const blackBoxFields = [
"BLACKBOX_FEATURE_NAV_ACC",
"BLACKBOX_FEATURE_NAV_POS",
"BLACKBOX_FEATURE_NAV_PID",
"BLACKBOX_FEATURE_MAG",
"BLACKBOX_FEATURE_ACC",
"BLACKBOX_FEATURE_ATTITUDE",
"BLACKBOX_FEATURE_RC_DATA",
"BLACKBOX_FEATURE_RC_COMMAND",
"BLACKBOX_FEATURE_MOTORS",
];
if (GUI.active_tab != 'onboard_logging') {
GUI.active_tab = 'onboard_logging';
googleAnalytics.sendAppView('onboard_logging');
}
if (CONFIGURATOR.connectionValid) {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() {
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, function() {
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
MSP.send_message(MSPCodes.MSP2_BLACKBOX_CONFIG, false, false, load_html);
@ -59,7 +72,7 @@ TABS.onboard_logging.initialize = function (callback) {
dataflashPresent = DATAFLASH.totalSize > 0,
blackboxSupport = false;
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(BF_CONFIG.features, 19)) {
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(FEATURES, 19)) {
blackboxSupport = true;
}
@ -97,7 +110,7 @@ TABS.onboard_logging.initialize = function (callback) {
BLACKBOX.blackboxRateNum = parseInt(rate[0], 10);
BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10);
BLACKBOX.blackboxDevice = parseInt($(".blackboxDevice select").val(), 10);
BLACKBOX.blackboxIncludeFlags = getIncludeFlags();
helper.features.reset();
helper.features.fromUI($('.require-blackbox-supported'));
helper.features.execute(function () {
@ -106,6 +119,29 @@ TABS.onboard_logging.initialize = function (callback) {
});
}
//Add checkboxes for each blackbox field
const blackboxFieldsDiv = $("#blackBoxFlagsDiv");
for (let i = 0; i < blackBoxFields.length; i++) {
const FIELD_ID = blackBoxFields[i];
const isEnabled = (BLACKBOX.blackboxIncludeFlags & 1<<i) !==0;
const input = $('<input type="checkbox" class="toggle feature" />')
input.attr("id",FIELD_ID);
input.attr("checked",isEnabled);
const label = $("<label></label>");
label.attr("for",FIELD_ID)
const span = $('<span></span>');
span.html(chrome.i18n.getMessage(FIELD_ID))
label.append(span);
const checkbox = $('<div class="checkbox"></div>')
.append([
input,label
])
blackboxFieldsDiv.append(checkbox);
}
populateLoggingRates();
populateDevices();
@ -389,6 +425,19 @@ TABS.onboard_logging.initialize = function (callback) {
eraseCancelled = true;
$(".dataflash-confirm-erase")[0].close();
}
function getIncludeFlags(){
let flags = 0;
for (let i = 0; i < blackBoxFields.length; i++) {
const FIELD_ID = blackBoxFields[i];
const checkbox = $("#"+FIELD_ID);
if(checkbox.prop("checked")){
flags=flags|1<<i;
}
}
return flags;
}
};
TABS.onboard_logging.cleanup = function (callback) {

View file

@ -8,14 +8,18 @@
<div class="spacer_box settings">
<div class="checkbox notifications">
<input id="notificationsOptions" type="checkbox" />
<label for="notificationsOptions"><span
data-i18n="options_receive_app_notifications"></span></label>
<label for="notificationsOptions"><span data-i18n="options_receive_app_notifications"></span></label>
</div>
<div class="checkbox notifications">
<div class="checkbox statistics">
<input id="improveConfigurator" type="checkbox" />
<label for="improveConfigurator"><span data-i18n="options_improve_configurator"></span></label>
</div>
<div class="checkbox show_profile_parameters">
<input id="showProfileParameters" type="checkbox" />
<label for="showProfileParameters"><span data-i18n="options_showProfileParameters"></span></label>
</div>
</div>
</div>

View file

@ -38,7 +38,7 @@
</div>
</div>
</div>
<div class="cf_column third_right">
<div class="cf_column third_right osd_settings">
<div class="gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="osd_video_format"></div>
@ -123,17 +123,17 @@
<span data-i18n="osd_time_alarm"></span>
</label>
<label for="osd_alt_alarm">
<input id="osd_alt_alarm" data-setting="osd_alt_alarm" data-setting-multiplier="1" type="number" data-step="1" />
<input id="osd_alt_alarm" data-setting="osd_alt_alarm" data-unit="m" data-setting-multiplier="1" type="number" data-step="1" />
<span data-i18n="osd_alt_alarm"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="osdAlarmMAX_NEG_ALTITUDE_HELP"></div>
<label for="osd_neg_alt_alarm">
<input id="osd_neg_alt_alarm" data-setting="osd_neg_alt_alarm" data-setting-multiplier="1" type="number" data-step="1" />
<input id="osd_neg_alt_alarm" data-setting="osd_neg_alt_alarm" data-unit="m" data-setting-multiplier="1" type="number" data-step="1" />
<span data-i18n="osd_neg_alt_alarm"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="osdAlarmDIST_HELP"></div>
<label for="osd_dist_alarm">
<input id="osd_dist_alarm" data-setting="osd_dist_alarm" data-setting-multiplier="1" type="number" data-step="1" />
<input id="osd_dist_alarm" data-setting="osd_dist_alarm" data-unit="m-lrg" data-setting-multiplier="1" type="number" data-step="1" />
<span data-i18n="osd_dist_alarm"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="osdAlarmGFORCE_HELP"></div>
@ -157,27 +157,27 @@
<span data-i18n="osd_current_alarm"></span>
</label>
<label for="imu_temp_alarm_min">
<input id="imu_temp_alarm_min" data-setting="osd_imu_temp_alarm_min" data-setting-multiplier="10" type="number" data-step="0.5" />
<input id="imu_temp_alarm_min" data-setting="osd_imu_temp_alarm_min" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
<span data-i18n="osd_imu_temp_alarm_min"></span>
</label>
<label for="imu_temp_alarm_max">
<input id="imu_temp_alarm_max" data-setting="osd_imu_temp_alarm_max" data-setting-multiplier="10" type="number" data-step="0.5" />
<input id="imu_temp_alarm_max" data-setting="osd_imu_temp_alarm_max" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
<span data-i18n="osd_imu_temp_alarm_max"></span>
</label>
<label for="baro_temp_alarm_min">
<input id="baro_temp_alarm_min" data-setting="osd_baro_temp_alarm_min" data-setting-multiplier="10" type="number" data-step="0.5" />
<input id="baro_temp_alarm_min" data-setting="osd_baro_temp_alarm_min" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
<span data-i18n="osd_baro_temp_alarm_min"></span>
</label>
<label for="baro_temp_alarm_max">
<input id="baro_temp_alarm_max" data-setting="osd_baro_temp_alarm_max" data-setting-multiplier="10" type="number" data-step="0.5" />
<input id="baro_temp_alarm_max" data-setting="osd_baro_temp_alarm_max" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
<span data-i18n="osd_baro_temp_alarm_max"></span>
</label>
<label for="esc_temp_alarm_min">
<input id="esc_temp_alarm_min" data-setting="osd_esc_temp_alarm_min" data-setting-multiplier="10" type="number" data-step="0.5" />
<input id="esc_temp_alarm_min" data-setting="osd_esc_temp_alarm_min" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
<span data-i18n="osd_esc_temp_alarm_min"></span>
</label>
<label for="esc_temp_alarm_max">
<input id="esc_temp_alarm_max" data-setting="osd_esc_temp_alarm_max" data-setting-multiplier="10" type="number" data-step="0.5" />
<input id="esc_temp_alarm_max" data-setting="osd_esc_temp_alarm_max" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
<span data-i18n="osd_esc_temp_alarm_max"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="osdalarmLQ_HELP"></div>
@ -221,11 +221,10 @@
<select data-setting="dji_message_speed_source" data-live="true"></select>
<span data-i18n="osd_dji_speed_source"></span>
</label>
<div class="djiCraftNameElements">
<input type="checkbox" id="useCraftnameForMessages" data-setting="dji_use_name_for_messages" data-live="true" class="toggle"/>
<span data-i18n="osd_dji_use_craft_name_elements"></span>
</div>
<label class="djiCraftNameElements">
<input type="checkbox" id="useCraftnameForMessages" data-setting="dji_use_name_for_messages" data-live="true" class="toggle"/>
<span data-i18n="osd_dji_use_craft_name_elements"></span>
</label>
<label>
<input type="checkbox" id="djiAdjustments" data-setting="dji_use_adjustments" data-live="true" class="toggle"></select>
<span data-i18n="osd_dji_adjustments"></span>

View file

@ -397,11 +397,8 @@ function osdMainBatteryPreview() {
if (Settings.getInputValue('osd_main_voltage_decimals') == 2) {
s += '3';
}
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
s += 'V';
} else {
s += FONT.symbol(SYM.VOLT);
}
s += FONT.symbol(SYM.VOLT);
return FONT.symbol(SYM.BATT) + FONT.embed_dot(s);
}
@ -781,28 +778,14 @@ OSD.constants = {
name: 'REMAINING_FLIGHT_DISTANCE',
id: 49,
preview: function(osd_data) {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.TRIP_DIST) + FONT.symbol(SYM.DIST_MI) + FONT.embed_dot('0.98');
case 4: // GA
return FONT.symbol(SYM.TRIP_DIST) + FONT.symbol(SYM.DIST_NM) + FONT.embed_dot('0.85');
default:
// Metric
return FONT.symbol(SYM.TRIP_DIST) + FONT.symbol(SYM.DIST_KM) + FONT.embed_dot('1.57');
}
} else {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.98') + FONT.symbol(SYM.DIST_MI);
case 4: // GA
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.85') + FONT.symbol(SYM.DIST_NM);
default: // Metric
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('1.73') + FONT.symbol(SYM.DIST_KM);
}
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.98') + FONT.symbol(SYM.DIST_MI);
case 4: // GA
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.85') + FONT.symbol(SYM.DIST_NM);
default: // Metric
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('1.73') + FONT.symbol(SYM.DIST_KM);
}
}
},
@ -1082,24 +1065,13 @@ OSD.constants = {
name: 'ALTITUDE',
id: 15,
preview: function () {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
case 4: // GA
return FONT.symbol(SYM.ALT_FT) + '375';
default: // Metric
return FONT.symbol(SYM.ALT_M) + '114'
}
} else {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
case 4: // GA
return ' 375' + FONT.symbol(SYM.ALT_FT);
default: // Metric
return ' 114' + FONT.symbol(SYM.ALT_M);
}
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
case 4: // GA
return ' 375' + FONT.symbol(SYM.ALT_FT);
default: // Metric
return ' 114' + FONT.symbol(SYM.ALT_M);
}
}
},
@ -1237,55 +1209,35 @@ OSD.constants = {
name: 'CURRENT_DRAW',
id: 11,
preview: function() {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
return FONT.symbol(SYM.AMP) + FONT.embed_dot('42.1');
} else {
return FONT.embed_dot('42.1') + FONT.symbol(SYM.AMP);
}
return FONT.embed_dot('42.1') + FONT.symbol(SYM.AMP);
}
},
{
name: 'MAH_DRAWN',
id: 12,
preview: function() {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
return FONT.symbol(SYM.MAH) + '690 '; // 4 chars
} else {
return '1034' + FONT.symbol(SYM.MAH); // 4 chars
}
return '1034' + FONT.symbol(SYM.MAH); // 4 chars
}
},
{
name: 'WH_DRAWN',
id: 36,
preview: function() {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
return FONT.symbol(SYM.WH) + FONT.embed_dot('1.25');
} else {
return FONT.embed_dot('1.25') + FONT.symbol(SYM.WH);
}
return FONT.embed_dot('1.25') + FONT.symbol(SYM.WH);
}
},
{
name: 'POWER',
id: 19,
preview: function() {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
return FONT.symbol(SYM.WATT) + '50 '; // 3 chars
} else {
return ' 69' + FONT.symbol(SYM.WATT); // 3 chars
}
return ' 69' + FONT.symbol(SYM.WATT); // 3 chars
}
},
{
name: 'MAIN_BATT_REMAINING_CAPACITY',
id: 37,
preview: function() {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
return FONT.symbol(SYM.MAH) + '690 '; // 4 chars
} else {
return '1276' + FONT.symbol(SYM.MAH); // 4 chars
}
return '1276' + FONT.symbol(SYM.MAH); // 4 chars
}
},
{
@ -1350,24 +1302,13 @@ OSD.constants = {
name: 'MSL_ALTITUDE',
id: 96,
preview: function(osd_data) {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
case 4: // GA
return FONT.symbol(SYM.ALT_FT) + '375';
default: // Metric
return FONT.symbol(SYM.ALT_M) + '114';
}
} else {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
case 4: // GA
return ' 375' + FONT.symbol(SYM.ALT_FT);
default: // Metric
return ' 114' + FONT.symbol(SYM.ALT_M);
}
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
case 4: // GA
return ' 375' + FONT.symbol(SYM.ALT_FT);
default: // Metric
return ' 114' + FONT.symbol(SYM.ALT_M);
}
},
},
@ -1483,26 +1424,14 @@ OSD.constants = {
name: 'DISTANCE_TO_HOME',
id: 23,
preview: function(osd_data) {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.HOME) + FONT.symbol(SYM.DIST_MI) + FONT.embed_dot('0.98');
case 4: // GA
return FONT.symbol(SYM.HOME) + FONT.symbol(SYM.DIST_NM) + FONT.embed_dot('0.85');
default: // Metric
return FONT.symbol(SYM.HOME) + FONT.symbol(SYM.DIST_KM) + FONT.embed_dot('1.57');
}
} else {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.HOME) + FONT.embed_dot('0.98') + FONT.symbol(SYM.DIST_MI);
case 4: // GA
return FONT.symbol(SYM.HOME) + FONT.embed_dot('0.85') + FONT.symbol(SYM.DIST_NM);
default: // Metric
return FONT.symbol(SYM.HOME) + FONT.embed_dot('1.57') + FONT.symbol(SYM.DIST_KM);
}
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.HOME) + FONT.embed_dot('0.98') + FONT.symbol(SYM.DIST_MI);
case 4: // GA
return FONT.symbol(SYM.HOME) + FONT.embed_dot('0.85') + FONT.symbol(SYM.DIST_NM);
default: // Metric
return FONT.symbol(SYM.HOME) + FONT.embed_dot('1.57') + FONT.symbol(SYM.DIST_KM);
}
}
},
@ -1511,26 +1440,14 @@ OSD.constants = {
id: 40,
min_version: '1.9.1',
preview: function(osd_data) {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.TRIP_DIST) + FONT.symbol(SYM.DIST_MI) + FONT.embed_dot('0.98');
case 4: // GA
return FONT.symbol(SYM.TRIP_DIST) + FONT.symbol(SYM.DIST_NM) + FONT.embed_dot('0.85');
default: // Metric
return FONT.symbol(SYM.TRIP_DIST) + FONT.symbol(SYM.DIST_KM) + FONT.embed_dot('1.57');
}
} else {
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.98') + FONT.symbol(SYM.DIST_MI);
case 4: // GA
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.85') + FONT.symbol(SYM.DIST_NM);
default: // Metric
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('1.57') + FONT.symbol(SYM.DIST_KM);
}
switch (OSD.data.preferences.units) {
case 0: // Imperial
case 3: // UK
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.98') + FONT.symbol(SYM.DIST_MI);
case 4: // GA
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('0.85') + FONT.symbol(SYM.DIST_NM);
default: // Metric
return FONT.symbol(SYM.TRIP_DIST) + FONT.embed_dot('1.57') + FONT.symbol(SYM.DIST_KM);
}
}
},
@ -2011,13 +1928,18 @@ OSD.updateDisplaySize = function () {
video_type = 'PAL';
}
// save the original OSD element positions.
var origPos = [];
for (var ii = 0; ii < OSD.data.items.length; ii++) {
origPos.push(OSD.msp.helpers.pack.position(OSD.data.items[ii]));
// save the original OSD element positions for all layouts
var osdLayouts = [];
for (var ii = 0; ii < OSD.data.layout_count; ii++) {
var items = OSD.data.layouts[ii];
var origPos = [];
for (var jj = 0; jj < OSD.data.items.length; jj++) {
origPos.push(OSD.msp.helpers.pack.position(items[jj]));
}
osdLayouts.push(origPos);
}
// save the new video type and cols per line
// set the new video type and cols per line
FONT.constants.SIZES.LINE = OSD.constants.VIDEO_COLS[video_type];
OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type;
@ -2028,16 +1950,20 @@ OSD.updateDisplaySize = function () {
total: OSD.constants.VIDEO_BUFFER_CHARS[video_type]
};
// recalculate the OSD element positions for the new cols per line
for (var ii = 0; ii < OSD.data.items.length; ii++) {
var item = OSD.msp.helpers.unpack.position(origPos[ii]);
// do not recalculate anything not visible or outside of the screen
if (item.isVisible && item.x < OSD.data.display_size.x && item.y < OSD.data.display_size.y) {
OSD.data.items[ii] = item;
}
}
// set the preview size
// re-calculate the OSD element positions for each layout
for (var ii = 0; ii < OSD.data.layout_count; ii++) {
var origPos = osdLayouts[ii];
var items = OSD.data.layouts[ii];
for (var jj = 0; jj < OSD.data.item_count; jj++) {
var item = OSD.msp.helpers.unpack.position(origPos[jj]);
// leave element alone if outside of screen (enable and disable element to relocate to 0,0)
if (item.x < OSD.data.display_size.x && item.y < OSD.data.display_size.y) {
items[jj] = item;
}
}
}
// set the preview size based on the video type
$('.third_left').toggleClass('preview_hd_side', (video_type == 'HD'))
$('.preview').toggleClass('preview_hd cut43_left', (video_type == 'HD'))
$('.third_right').toggleClass('preview_hd_side', (video_type == 'HD'))
@ -2094,7 +2020,7 @@ OSD.msp = {
},
pack: {
position: function (display_item) {
return (display_item.isVisible ? 0x2000 : 0)
return (display_item.isVisible ? OSD.constants.VISIBLE : 0)
| ((display_item.y & 0x3F) << 6) | (display_item.x & 0x3F);
}
}
@ -2108,12 +2034,10 @@ OSD.msp = {
result.push16(OSD.data.alarms.max_altitude);
result.push16(OSD.data.alarms.dist);
result.push16(OSD.data.alarms.max_neg_altitude);
if (semver.gte(CONFIG.flightControllerVersion, '2.2.0')) {
result.push16(OSD.data.alarms.gforce);
result.push16(OSD.data.alarms.gforce_axis_min);
result.push16(OSD.data.alarms.gforce_axis_max);
result.push8(OSD.data.alarms.current);
}
result.push16(OSD.data.alarms.gforce);
result.push16(OSD.data.alarms.gforce_axis_min);
result.push16(OSD.data.alarms.gforce_axis_max);
result.push8(OSD.data.alarms.current);
result.push16(OSD.data.alarms.imu_temp_alarm_min);
result.push16(OSD.data.alarms.imu_temp_alarm_max);
result.push16(OSD.data.alarms.baro_temp_alarm_min);
@ -2129,12 +2053,10 @@ OSD.msp = {
OSD.data.alarms.max_altitude = alarms.readU16();
OSD.data.alarms.dist = alarms.readU16();
OSD.data.alarms.max_neg_altitude = alarms.readU16();
if (semver.gte(CONFIG.flightControllerVersion, '2.2.0')) {
OSD.data.alarms.gforce = alarms.readU16();
OSD.data.alarms.gforce_axis_min = alarms.read16();
OSD.data.alarms.gforce_axis_max = alarms.read16();
OSD.data.alarms.current = alarms.readU8();
}
OSD.data.alarms.gforce = alarms.readU16();
OSD.data.alarms.gforce_axis_min = alarms.read16();
OSD.data.alarms.gforce_axis_max = alarms.read16();
OSD.data.alarms.current = alarms.readU8();
OSD.data.alarms.imu_temp_alarm_min = alarms.read16();
OSD.data.alarms.imu_temp_alarm_max = alarms.read16();
OSD.data.alarms.baro_temp_alarm_min = alarms.read16();
@ -2514,14 +2436,16 @@ OSD.GUI.updateFields = function() {
}
}
$('#djiUnsupportedElements').prepend(
$('<input type="checkbox" class="toggle" />')
.attr('checked', OSD.data.isDjiHdFpv)
.on('change', function () {
OSD.GUI.updateDjiView(this.checked);
OSD.GUI.updatePreviews();
})
);
if ($('#djiUnsupportedElementsToggle').length == false) {
$('#djiUnsupportedElements').prepend(
$('<input id="djiUnsupportedElementsToggle" type="checkbox" class="toggle" />')
.attr('checked', OSD.data.isDjiHdFpv)
.on('change', function () {
OSD.GUI.updateDjiView(this.checked);
OSD.GUI.updatePreviews();
})
);
}
// TODO: If we add more switches somewhere else, this
// needs to be called after all of them have been set up
GUI.switchery();

View file

@ -54,14 +54,14 @@
</div>
<div id="throttle_idle-info" class="info-box"></div>
<div class="number requires-v2_4">
<div class="number">
<input id="throttle_idle" data-setting="throttle_idle" type="number" data-step="1.0" />
<label for="throttle_idle">
<span data-i18n="throttleIdle"></span>
</label>
</div>
<div class="number requires-v2_4">
<div class="number">
<input id="motor_poles" data-setting="motor_poles" type="number" />
<label for="motor_poles">
<span data-i18n="motor_poles"></span>

View file

@ -1,4 +1,4 @@
/*global helper,MSP,MSPChainerClass,googleAnalytics,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM_MULTIROTOR,BF_CONFIG,PLATFORM_TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
/*global helper,MSP,MSPChainerClass,googleAnalytics,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM_MULTIROTOR,PLATFORM_TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
'use strict';
TABS.outputs = {
@ -24,7 +24,7 @@ TABS.outputs.initialize = function (callback) {
loadChainer.setChain([
mspHelper.loadMiscV2,
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.load3dConfig,
mspHelper.loadMotors,
mspHelper.loadMotorMixRules,
@ -46,7 +46,6 @@ TABS.outputs.initialize = function (callback) {
saveSettings,
mspHelper.sendServoConfigurations,
mspHelper.saveAdvancedConfig,
mspHelper.saveBfConfig,
mspHelper.saveMiscV2,
mspHelper.saveToEeprom
]);
@ -65,18 +64,12 @@ TABS.outputs.initialize = function (callback) {
function onLoad() {
self.feature3DEnabled = bit_check(BF_CONFIG.features, 12);
self.feature3DEnabled = bit_check(FEATURES, 12);
process_motors();
process_servos();
processConfiguration();
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
$('.requires-v2_4').show();
} else {
$('.requires-v2_4').hide();
}
finalize();
}
@ -193,7 +186,7 @@ TABS.outputs.initialize = function (callback) {
$('#servo-rate-container').show();
helper.features.updateUI($('.tab-motors'), BF_CONFIG.features);
helper.features.updateUI($('.tab-motors'), FEATURES);
GUI.simpleBind();
let $reversibleMotorCheckbox = $('#feature-12');

289
tabs/pid_tuning.html Executable file → Normal file
View file

@ -3,100 +3,100 @@
<div class="tab-pid_tuning toolbar_fixed_bottom">
<div class="content_wrapper">
<div class="tab_title subtab__header">
<span class="subtab__header_label subtab__header_label--current" for="subtab-pid">PID gains</span>
<span class="subtab__header_label" for="subtab-rates">Rates & Expo</span>
<span class="subtab__header_label" for="subtab-filters">Filters</span>
<span class="subtab__header_label" for="subtab-mechanics">Mechanics</span>
<span class="subtab__header_label subtab__header_label--current" for="subtab-pid" data-i18n="pidTuning_PIDgains"></span>
<span class="subtab__header_label" for="subtab-rates" data-i18n="pidTuning_RatesAndExpo"></span>
<span class="subtab__header_label" for="subtab-filters" data-i18n="pidTuning_Filters"></span>
<span class="subtab__header_label" for="subtab-mechanics" data-i18n="pidTuning_Mechanics"></span>
</div>
<div id="subtab-pid" class="subtab__content subtab__content--current">
<div class="cf_column right" style="margin-top: -6px;">
<div class="default_btn show">
<a href="#" id="showAllPids">Show all PIDs</a>
<a href="#" id="showAllPids" data-i18n="pidTuning_ShowAllPIDs"></a>
</div>
<div class="default_btn resetbt">
<a href="#" id="resetDefaults">Select New Defaults</a>
<a href="#" id="resetDefaults" data-i18n="pidTuning_SelectNewDefaults"></a>
</div>
<div class="default_btn resetbt">
<a href="#" id="resetPIDs">Reset PID Controller</a>
<a href="#" id="resetPIDs" data-i18n="pidTuning_ResetPIDController"></a>
</div>
</div>
<div class="tab_subtitle" style="margin-top: 1em;">PID gains</div>
<div class="tab_subtitle" style="margin-top: 1em;" data-i18n="pidTuning_PIDgains"></div>
<div class="clear-both"></div>
<div class="cf_column pid-section">
<div class="gui_box grey">
<table class="pid_titlebar">
<tr>
<th class="name" data-i18n="pidTuningName"></th>
<th class="proportional" data-i18n="pidTuningProportional"></th>
<th class="integral" data-i18n="pidTuningIntegral"></th>
<th class="derivative" data-i18n="pidTuningDerivative"></th>
<th class="feedforward" data-i18n="pidTuningFeedForward"></th>
<th class="name" data-i18n="pidTuning_Name"></th>
<th class="proportional" data-i18n="pidTuning_Proportional"></th>
<th class="integral" data-i18n="pidTuning_Integral"></th>
<th class="derivative" data-i18n="pidTuning_Derivative"></th>
<th class="feedforward" data-i18n="pidTuning_FeedForward"></th>
</tr>
</table>
<table id="pid_main" class="pid_tuning">
<tr>
<th colspan="5">
<div class="pid_mode" data-i18n="pidTuningBasic"></div>
<div class="pid_mode" data-i18n="pidTuning_Basic"></div>
</th>
</tr>
<tr class="ROLL" data-pid-bank-position="0">
<!-- 0 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" class="rpy_d" name="d" step="1" min="0" max="255" /></td>
<td><input type="number" class="rpy_ff" name="ff" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" class="rpy_d" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" class="rpy_ff" name="ff" step="1" min="0" max="255" /></td>
</tr>
<tr class="PITCH" data-pid-bank-position="1">
<!-- 1 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" class="rpy_d" name="d" step="1" min="0" max="255" /></td>
<td><input type="number" class="rpy_ff" name="ff" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" class="rpy_d" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" class="rpy_ff" name="ff" step="1" min="0" max="255" /></td>
</tr>
<tr class="YAW" data-pid-bank-position="2">
<!-- 2 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" class="rpy_d" name="d" step="1" min="0" max="255" /></td>
<td><input type="number" class="rpy_ff" name="ff" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" class="rpy_d" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" class="rpy_ff" name="ff" step="1" min="0" max="255" /></td>
</tr>
</table>
<table id="pid_baro" class="pid_tuning">
<tr>
<th colspan="5">
<div class="pid_mode" data-i18n="pidTuningAltitude"></div>
<div class="pid_mode" data-i18n="pidTuning_Altitude"></div>
</th>
</tr>
<tr class="ALT" data-pid-bank-position="3">
<!-- 3 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="d" step="1" min="0" max="255" /></td>
<td></td>
</tr>
<tr class="Vario" data-pid-bank-position="9">
<!-- 9 -->
<td>VEL</td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="d" step="1" min="0" max="255" /></td>
<td></td>
</tr>
</table>
<table id="pid_mag" class="pid_tuning">
<tr>
<th colspan="5">
<div class="pid_mode" data-i18n="pidTuningMag"></div>
<div class="pid_mode" data-i18n="pidTuning_Mag"></div>
</th>
</tr>
<tr class="MAG" data-pid-bank-position="8">
<!-- 8 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td></td>
<td></td>
<td></td>
@ -104,22 +104,22 @@
<tr class="HEADING" data-pid-bank-position="10">
<!-- 8 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="d" step="1" min="0" max="255" /></td>
<td></td>
</tr>
</table>
<table id="pid_gps" class="pid_tuning">
<tr>
<th colspan="5">
<div class="pid_mode" data-i18n="pidTuningGps"></div>
<div class="pid_mode" data-i18n="pidTuning_GPS"></div>
</th>
</tr>
<tr class="Pos" data-pid-bank-position="4">
<!-- 4 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td></td>
<td></td>
<td></td>
@ -127,10 +127,10 @@
<tr class="PosR" data-pid-bank-position="5">
<!-- 5 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
<td><input type="number" name="ff" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="ff" step="1" min="0" max="255" /></td>
</tr>
<tr class="NavR" data-pid-bank-position="6">
<!-- 6 -->
@ -148,21 +148,21 @@
<th colspan="4">
<div class="pid_mode borderleft">
<div class="textleft">
<div class="pidTuningLevel" data-i18n="pidTuningLevel"></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuningLevelHelp"></div>
<div class="pidTuningLevel" data-i18n="pidTuning_Level"></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_LevelHelp"></div>
</div>
<div class="pids" data-i18n="pidTuningLevelP"></div>
<div class="pids" data-i18n="pidTuningLevelI"></div>
<div class="pids" data-i18n="pidTuningLevelD"></div>
<div class="pids" data-i18n="pidTuning_LevelP"></div>
<div class="pids" data-i18n="pidTuning_LevelI"></div>
<div class="pids" data-i18n="pidTuning_LevelD"></div>
</div>
</th>
</tr>
<tr class="LEVEL" data-pid-bank-position="7">
<!-- 7 -->
<td></td>
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="p" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="i" step="1" min="0" max="255" /></td>
<td><input class="controlProfileHighlight" type="number" name="d" step="1" min="0" max="255" /></td>
</tr>
</table>
</div>
@ -170,89 +170,78 @@
</div>
<div id="subtab-rates" class="subtab__content">
<div class="tab_subtitle" style="margin-top: 1em;">Rates & Expo</div>
<div class="tab_subtitle" style="margin-top: 1em;" data-i18n="pidTuning_RatesAndExpo"></div>
<div class="clear-both"></div>
<div class="cf_column">
<table class="settings-table settings-table--inav">
<tbody>
<tr>
<th class="roll" data-i18n="pidTuningRollRate"></th>
<th class="roll" data-i18n="pidTuning_RollRate"></th>
<td class="roll">
<input type="number" id="rate-roll" class="rate-tpa_input" step="10" min="40"
max="1800" />
degrees per second
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="roll_rate" data-unit="decadegps" /></div>
</td>
</tr>
<tr>
<th class="pitch" data-i18n="pidTuningPitchRate"></th>
<th class="pitch" data-i18n="pidTuning_PitchRate"></th>
<td class="pitch">
<input type="number" id="rate-pitch" class="rate-tpa_input" step="10" min="40"
max="1800" /> degrees per second
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="pitch_rate" data-unit="decadegps" /></div>
</td>
</tr>
<tr>
<th class="yaw" data-i18n="pidTuningYawRate"></th>
<th class="yaw" data-i18n="pidTuning_YawRate"></th>
<td class="yaw">
<input type="number" id="rate-yaw" class="rate-tpa_input" step="10" min="10"
max="1800" />
degrees per second
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="yaw_rate" data-unit="decadegps" /></div>
</td>
</tr>
<tr>
<th>Roll & Pitch Expo</th>
<th data-i18n="pidTuning_RollAndPitchExpo"></th>
<td>
<input data-setting="rc_expo" type="number" class="rate-tpa_input" />
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="rc_expo" data-unit="percent" /></div>
</td>
</tr>
<tr>
<th>Yaw Expo</th>
<th data-i18n="pidTuning_YawExpo"></th>
<td>
<input data-setting="rc_yaw_expo" type="number" class="rate-tpa_input" />
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="rc_yaw_expo" data-unit="percent" /></div>
</td>
</tr>
<tr>
<th data-i18n="pidTuningMaxRollAngle"></th>
<th data-i18n="pidTuning_MaxRollAngle"></th>
<td>
<input data-setting="max_angle_inclination_rll" data-setting-multiplier="10"
type="number" class="rate-tpa_input" /> degrees
<div class="helpicon cf_tip" data-i18n_title="pidTuningMaxRollAngleHelp"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="max_angle_inclination_rll" data-unit="decideg-lrg" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_MaxRollAngleHelp"></div>
</td>
</tr>
<tr>
<th data-i18n="pidTuningMaxPitchAngle"></th>
<th data-i18n="pidTuning_MaxPitchAngle"></th>
<td>
<input data-setting="max_angle_inclination_pit" data-setting-multiplier="10"
type="number" class="rate-tpa_input" /> degrees
<div class="helpicon cf_tip" data-i18n_title="pidTuningMaxPitchAngleHelp"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="max_angle_inclination_pit" data-unit="decideg-lrg" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_MaxPitchAngleHelp"></div>
</td>
</tr>
<tr>
<th data-i18n="magHoldYawRate"></th>
<th data-i18n="pidTuning_magHoldYawRate"></th>
<td>
<input type="number" id="magHoldYawRate" class="rate-tpa_input" step="5" min="10"
max="250" /> degrees per second
<div class="helpicon cf_tip" data-i18n_title="pidTuningMagHoldYawRateHelp"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="heading_hold_rate_limit" data-unit="degps" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_MagHoldYawRateHelp"></div>
</td>
</tr>
<tr>
<th class="roll" data-i18n="pidTuningManualRollRate"></th>
<th class="roll" data-i18n="pidTuning_ManualRollRate"></th>
<td class="roll">
<input type="number" id="rate-manual-roll" class="rate-tpa_input" step="1" min="0"
max="100" /> %
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="manual_roll_rate" data-unit="percent" /></div>
</td>
</tr>
<tr>
<th class="pitch" data-i18n="pidTuningManualPitchRate"></th>
<th class="pitch" data-i18n="pidTuning_ManualPitchRate"></th>
<td class="pitch">
<input type="number" id="rate-manual-pitch" class="rate-tpa_input" step="1" min="0"
max="100" /> %
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="manual_pitch_rate" data-unit="percent" /></div>
</td>
</tr>
<tr>
<th class="yaw" data-i18n="pidTuningManualYawRate"></th>
<th class="yaw" data-i18n="pidTuning_ManualYawRate"></th>
<td class="yaw">
<input type="number" id="rate-manual-yaw" class="rate-tpa_input" step="1" min="0"
max="100" /> %
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="manual_yaw_rate" data-unit="percent" /></div>
</td>
</tr>
</tbody>
@ -261,36 +250,36 @@
</div>
<div id="subtab-filters" class="subtab__content">
<div class="tab_subtitle" data-i18n="mainFilters" style="margin-top: 1em;"></div>
<div class="tab_subtitle" data-i18n="pidTuning_mainFilters" style="margin-top: 1em;"></div>
<div class="clear-both"></div>
<div class="cf_column">
<table class="settings-table settings-table--filtering">
<tbody>
<tr>
<th data-i18n="gyro_main_lpf_hz"></th>
<th data-i18n="pidTuning_gyro_main_lpf_hz"></th>
<td>
<input data-setting="gyro_main_lpf_hz" type="number" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="gyro_main_lpf_hz_help"></div>
<div class="pidTuning_number"><input data-setting="gyro_main_lpf_hz" type="number" class="rate-tpa_input" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_gyro_main_lpf_hz_help"></div>
</td>
</tr>
<tr>
<th>Matrix Filter Min Frequency</th>
<th data-i18n="pidTuning_MatrixFilterMinFrequency"></th>
<td>
<input data-setting="dynamic_gyro_notch_min_hz" type="number" class="rate-tpa_input" />
<div class="helpicon cf_tip" title="Minimum frequency for the Matrix Filter. Value should depends on propeller size. 150Hz work fine with 5&quot; and smaller. For 7&quot; and above lower even below 100Hz."></div>
<div class="pidTuning_number"><input data-setting="dynamic_gyro_notch_min_hz" type="number" class="rate-tpa_input" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_MatrixFilterMinFrequencyHelp"></div>
</td>
</tr>
<tr>
<th>Matrix Filter Q Factor</th>
<th data-i18n="pidTuning_MatrixFilterQFactor"></th>
<td>
<input data-setting="dynamic_gyro_notch_q" type="number" class="rate-tpa_input" />
<div class="helpicon cf_tip" title="The higher value, the higher selectivity of the Matrix Filter. Values between 150 and 300 are recommended"></div>
<div class="pidTuning_number"><input data-setting="dynamic_gyro_notch_q" type="number" class="rate-tpa_input" /></div>
<div class="helpicon cf_tip" title=""></div>
</td>
</tr>
<tr>
<th>Unicorn Filter Q Factor</th>
<th data-i18n="pidTuning_UnicornFilterQFactor"></th>
<td>
<input data-setting="setpoint_kalman_q" type="number" class="rate-tpa_input" />
<div class="pidTuning_number"><input data-setting="setpoint_kalman_q" type="number" class="rate-tpa_input" /></div>
</td>
</tr>
</tbody>
@ -298,36 +287,36 @@
</div>
<div class="clear-both"></div>
<div class="tab_subtitle" data-i18n="dtermFilters" style="margin-top: 1em;"></div>
<div class="tab_subtitle" data-i18n="pidTuning_dtermFilters" style="margin-top: 1em;"></div>
<div class="cf_column">
<table class="settings-table settings-table--filtering">
<tbody>
<tr>
<th data-i18n="dtermLpfCutoffFrequency"></th>
<th data-i18n="pidTuning_dtermLpfCutoffFrequency"></th>
<td>
<input data-setting="dterm_lpf_hz" type="number" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="dtermLpfCutoffFrequencyHelp"></div>
<div class="pidTuning_number"><input data-setting="dterm_lpf_hz" type="number" class="rate-tpa_input" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_dtermLpfCutoffFrequencyHelp"></div>
</td>
</tr>
</tbody>
</table>
</div>
<div class="clear-both requires-v2_4"></div>
<div class="tab_subtitle requires-v2_4" data-i18n="rpmFilters" style="margin-top: 1em;"></div>
<div class="cf_column requires-v2_4">
<div class="clear-both"></div>
<div class="tab_subtitle" data-i18n="pidTuning_rpmFilters" style="margin-top: 1em;"></div>
<div class="cf_column">
<table class="settings-table settings-table--filtering">
<tbody>
<tr>
<th data-i18n="rpm_gyro_filter_enabled"></th>
<th data-i18n="pidTuning_rpm_gyro_filter_enabled"></th>
<td>
<select data-setting="rpm_gyro_filter_enabled" />
<div class="pidTuning_number"><input type="checkbox" class="toggle update_preview" data-setting="rpm_gyro_filter_enabled" /></div>
</td>
</tr>
<tr>
<th data-i18n="rpm_gyro_min_hz"></th>
<th data-i18n="pidTuning_rpm_gyro_min_hz"></th>
<td>
<input data-setting="rpm_gyro_min_hz" type="number" class="rate-tpa_input" />
<div class="pidTuning_number"><input data-setting="rpm_gyro_min_hz" type="number" class="rate-tpa_input" /></div>
</td>
</tr>
</tbody>
@ -337,40 +326,40 @@
<div id="subtab-mechanics" class="subtab__content">
<div class="clear-both"></div>
<div class="tab_subtitle" data-i18n="iTermMechanics" style="margin-top: 1em;"></div>
<div class="tab_subtitle" data-i18n="pidTuning_ITermMechanics" style="margin-top: 1em;"></div>
<div class="cf_column">
<table class="settings-table settings-table--filtering">
<tbody>
<tr>
<th data-i18n="itermRelaxCutoff"></th>
<th data-i18n="pidTuning_itermRelaxCutoff"></th>
<td>
<input data-setting="mc_iterm_relax_cutoff" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="itermRelaxCutoffHelp"></div>
<div class="pidTuning_number"><input type="number" data-setting="mc_iterm_relax_cutoff" class="rate-tpa_input" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_itermRelaxCutoffHelp"></div>
</td>
</tr>
<tr>
<th data-i18n="antigravityGain"></th>
<th data-i18n="pidTuning_antigravityGain"></th>
<td>
<input class="rate-tpa_input" data-setting="antigravity_gain" />
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="antigravity_gain" data-step="0.001" /></div>
</td>
</tr>
<tr>
<th data-i18n="antigravityAccelerator"></th>
<th data-i18n="pidTuning_antigravityAccelerator"></th>
<td>
<input class="rate-tpa_input" data-setting="antigravity_accelerator" />
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="antigravity_accelerator" data-step="0.001" /></div>
</td>
</tr>
<tr>
<th data-i18n="antigravityCutoff"></th>
<th data-i18n="pidTuning_antigravityCutoff"></th>
<td>
<input class="rate-tpa_input" data-setting="antigravity_cutoff_lpf_hz" />
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="antigravity_cutoff_lpf_hz" /></div>
</td>
</tr>
<tr>
<th data-i18n="itermBankAngleFreeze"></th>
<th data-i18n="pidTuning_itermBankAngleFreeze"></th>
<td>
<input class="rate-tpa_input" data-setting="fw_yaw_iterm_freeze_bank_angle" type="number" step="1" min="0" max="90" />
<div class="helpicon cf_tip" data-i18n_title="itermBankAngleFreezeHelp"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="fw_yaw_iterm_freeze_bank_angle" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_itermBankAngleFreezeHelp"></div>
</td>
</tr>
</tbody>
@ -378,36 +367,36 @@
</div>
<div class="clear-both"></div>
<div class="tab_subtitle" data-i18n="dTermMechanics" style="margin-top: 1em;"></div>
<div class="tab_subtitle" data-i18n="pidTuning_dTermMechanics" style="margin-top: 1em;"></div>
<div class="cf_column">
<table class="settings-table settings-table--filtering">
<tbody>
<tr>
<th data-i18n="d_boost_min"></th>
<th data-i18n="pidTuning_d_boost_min"></th>
<td>
<input data-setting="d_boost_min" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="d_boost_min_help"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="d_boost_min" data-step="0.001" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_d_boost_min_help"></div>
</td>
</tr>
<tr>
<th data-i18n="d_boost_max"></th>
<th data-i18n="pidTuning_d_boost_max"></th>
<td>
<input data-setting="d_boost_max" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="d_boost_max_help"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="d_boost_max" data-step="0.001" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_d_boost_max_help"></div>
</td>
</tr>
<tr>
<th data-i18n="d_boost_max_at_acceleration"></th>
<th data-i18n="pidTuning_d_boost_max_at_acceleration"></th>
<td>
<input data-setting="d_boost_max_at_acceleration" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="d_boost_max_at_acceleration_help"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="d_boost_max_at_acceleration" data-step="0.001" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_d_boost_max_at_acceleration_help"></div>
</td>
</tr>
<tr>
<th data-i18n="d_boost_gyro_delta_lpf_hz"></th>
<th data-i18n="pidTuning_d_boost_gyro_delta_lpf_hz"></th>
<td>
<input data-setting="d_boost_gyro_delta_lpf_hz" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="d_boost_gyro_delta_lpf_hz_help"></div>
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="d_boost_gyro_delta_lpf_hz" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_d_boost_gyro_delta_lpf_hz_help"></div>
</td>
</tr>
</tbody>
@ -415,37 +404,35 @@
</div>
<div class="clear-both"></div>
<div class="tab_subtitle" data-i18n="tpaMechanics" style="margin-top: 1em;"></div>
<div class="tab_subtitle" data-i18n="pidTuning_tpaMechanics" style="margin-top: 1em;"></div>
<div class="cf_column" style="margin-top:1em;">
<table class="settings-table settings-table--misc">
<tr>
<th data-i18n="pidTuningTPA"></th>
<th data-i18n="pidTuning_TPA"></th>
<td>
<input type="number" class="rate-tpa_input" id="tpa" step="1" min="0" max="100" />
%
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="tpa_rate" data-unit="percent" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuningTPAHelp"></div>
</td>
</tr>
<tr>
<th data-i18n="pidTuningTPABreakPoint"></th>
<th data-i18n="pidTuning_TPABreakPoint"></th>
<td>
<input type="number" class="rate-tpa_input" id="tpa-breakpoint" step="10" min="1000"
max="2000" />
<div class="pidTuning_number"><input type="number" class="rate-tpa_input" data-setting="tpa_breakpoint" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuningTPABreakPointHelp"></div>
</td>
</tr>
</table>
</div>
<div class="clear-both"></div>
<div class="tab_subtitle" data-i18n="fwLevelTrimMechanics" style="margin-top: 1em;"></div>
<div class="tab_subtitle" data-i18n="pidTuning_fwLevelTrimMechanics" style="margin-top: 1em;"></div>
<div class="cf_column">
<table class="settings-table settings-table--filtering">
<tbody>
<tr>
<th data-i18n="fw_level_pitch_trim"></th>
<th data-i18n="pidTuning_fw_level_pitch_trim"></th>
<td>
<input data-setting="fw_level_pitch_trim" class="rate-tpa_input" />
<div class="helpicon cf_tip" data-i18n_title="fw_level_pitch_trim_help"></div>
<div class="pidTuning_number"><input class="rate-tpa_input" data-setting="fw_level_pitch_trim" data-unit="deg" /></div>
<div class="helpicon cf_tip" data-i18n_title="pidTuning_fw_level_pitch_trim_help"></div>
</td>
</tr>
</tbody>
@ -456,10 +443,10 @@
<div class="clear-both"></div>
<div class="content_toolbar">
<div class="btn save_btn">
<a class="update" href="#" data-i18n="pidTuningButtonSave"></a>
<a class="update" href="#" data-i18n="pidTuning_ButtonSave"></a>
</div>
<div class="btn refresh_btn">
<a class="refresh" href="#" data-i18n="pidTuningButtonRefresh"></a>
<a class="refresh" href="#" data-i18n="pidTuning_ButtonRefresh"></a>
</div>
</div>
</div>

53
tabs/pid_tuning.js Executable file → Normal file
View file

@ -15,7 +15,7 @@ TABS.pid_tuning.initialize = function (callback) {
mspHelper.loadINAVPidConfig,
mspHelper.loadPidAdvanced,
mspHelper.loadFilterConfig,
mspHelper.loadBfConfig
mspHelper.loadFeatures
];
loadChain.push(mspHelper.loadRateProfileData);
@ -101,7 +101,7 @@ TABS.pid_tuning.initialize = function (callback) {
if (have_sensor(sensors_detected, 'mag')) {
$('#pid_mag').show();
}
if (bit_check(BF_CONFIG.features, 7)) { //This will need to be reworked to remove BF_CONFIG reference eventually
if (bit_check(FEATURES, 7)) {
$('#pid_gps').show();
}
if (have_sensor(sensors_detected, 'sonar')) {
@ -112,27 +112,8 @@ TABS.pid_tuning.initialize = function (callback) {
// translate to user-selected language
localize();
if (FC.isCdComponentUsed()) {
$('th.feedforward').html(chrome.i18n.getMessage('pidTuningControlDerivative'));
$('th.feedforward').attr('title', chrome.i18n.getMessage('pidTuningControlDerivative'));
}
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
$('.requires-v2_4').show();
} else {
$('.requires-v2_4').hide();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
$('.requires-v2_6').show();
$('.hides-v2_6').hide();
} else {
$('.requires-v2_6').hide();
$('.hides-v2_6').show();
}
helper.tabs.init($('.tab-pid_tuning'));
helper.features.updateUI($('.tab-pid_tuning'), BF_CONFIG.features);
helper.features.updateUI($('.tab-pid_tuning'), FEATURES);
hideUnusedPids(CONFIG.activeSensors);
@ -148,24 +129,30 @@ TABS.pid_tuning.initialize = function (callback) {
}
});
$('#resetPIDs').on('click', function(){
MSP.send_message(MSPCodes.MSP_SET_RESET_CURR_PID, false, false, false);
updateActivatedTab();
$('#resetPIDs').on('click', function() {
if (confirm(chrome.i18n.getMessage('confirm_reset_pid'))) {
MSP.send_message(MSPCodes.MSP_SET_RESET_CURR_PID, false, false, false);
updateActivatedTab();
}
});
$('#resetDefaults').on('click', function() {
mspHelper.setSetting("applied_defaults", 0, function() {
mspHelper.saveToEeprom( function () {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
if (confirm(chrome.i18n.getMessage('confirm_select_defaults'))) {
mspHelper.setSetting("applied_defaults", 0, function() {
mspHelper.saveToEeprom( function () {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
});
});
});
}
});
pid_and_rc_to_form();

View file

@ -131,15 +131,6 @@ TABS.ports.initialize = function (callback) {
'115200'
];
var telemetryBaudRates_pre1_6_3 = [
'AUTO',
'9600',
'19200',
'38400',
'57600',
'115200'
];
var telemetryBaudRates_post1_6_3 = [
'AUTO',
'1200',
@ -210,9 +201,8 @@ TABS.ports.initialize = function (callback) {
}
$elements = $('select.telemetry_baudrate');
var telemetryBaudRates = semver.gte(CONFIG.flightControllerVersion, "1.6.3") ? telemetryBaudRates_post1_6_3 : telemetryBaudRates_pre1_6_3;
for (i = 0; i < telemetryBaudRates.length; i++) {
$elements.append('<option value="' + telemetryBaudRates[i] + '">' + telemetryBaudRates[i] + '</option>');
for (i = 0; i < telemetryBaudRates_post1_6_3.length; i++) {
$elements.append('<option value="' + telemetryBaudRates_post1_6_3[i] + '">' + telemetryBaudRates_post1_6_3[i] + '</option>');
}
$elements = $('select.blackbox_baudrate');

View file

@ -80,8 +80,8 @@
<th data-i18n="receiverThrottleExpo"></th>
</tr>
<tr>
<td><input type="number" name="mid" step="0.01" min="0" max="1" /></td>
<td><input type="number" name="expo" step="0.01" min="0" max="1" /></td>
<td><input class="controlProfileHighlight" type="number" name="mid" step="0.01" min="0" max="1" /></td>
<td><input class="controlProfileHighlight" type="number" name="expo" step="0.01" min="0" max="1" /></td>
</tr>
</table>
<table class="deadband">
@ -125,8 +125,8 @@
<th data-i18n="receiverManualRcExpo"></th>
</tr>
<tr>
<td><input type="number" name="expo" step="0.01" min="0" max="2" /></td>
<td><input type="number" name="manual_expo" step="0.01" min="0" max="1" /></td>
<td><input class="controlProfileHighlight" type="number" name="expo" step="0.01" min="0" max="2" /></td>
<td><input class="controlProfileHighlight" type="number" name="manual_expo" step="0.01" min="0" max="1" /></td>
</tr>
</table>
<table class="yaw_rate" style="margin-bottom: 0;">
@ -135,8 +135,8 @@
<th data-i18n="receiverManualRcYawExpo"></th>
</tr>
<tr>
<td><input type="number" name="yaw_expo" step="0.01" min="0" max="2" /></td>
<td><input type="number" name="manual_yaw_expo" step="0.01" min="0" max="1" /></td>
<td><input class="controlProfileHighlight" type="number" name="yaw_expo" step="0.01" min="0" max="2" /></td>
<td><input class="controlProfileHighlight" type="number" name="manual_yaw_expo" step="0.01" min="0" max="1" /></td>
</tr>
</table>
</div>

View file

@ -1,4 +1,4 @@
/*global $,chrome,FC,helper,mspHelper,MIXER_CONFIG,BF_CONFIG*/
/*global $,chrome,FC,helper,mspHelper,MIXER_CONFIG*/
'use strict';
TABS.setup = {
@ -22,12 +22,12 @@ TABS.setup.initialize = function (callback) {
var loadChainer = new MSPChainerClass();
var loadChain = [
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.queryFcStatus,
mspHelper.loadMixerConfig
mspHelper.loadMixerConfig,
mspHelper.loadMiscV2
];
loadChain.push(mspHelper.loadMiscV2);
loadChainer.setChain(loadChain);
loadChainer.setExitPoint(load_html);
loadChainer.execute();

View file

@ -1,48 +0,0 @@
<div class="tab-transponder toolbar_fixed_bottom">
<div class="content_wrapper">
<div class="tab_title" i18n="tabTransponder">Transponder</div>
<div class="require-transponder-unsupported note">
<div class="note_spacer">
<p i18n="transponderNotSupported"></p>
</div>
</div>
<div class="require-transponder-supported">
<div class="note" style="margin-bottom: 20px;">
<div class="note_spacer">
<p i18n="transponderHelp"></p>
</div>
</div>
<div class="gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" i18n="transponderConfiguration"></div>
</div>
<div class="spacer_box">
<div class="text transponderData">
<div class="textspacer" >
<input type="text" name="data" spellcheck="false"/>
</div>
<label for="failsafe_feature_new"><span i18n="transponderData"></span>
</label>
<div class="helpicon cf_tip" i18n_title="transponderDataHelp"></div>
</div>
</div>
</div>
<div class="clear-both"></div>
</div>
<div class="note">
<div class="note_spacer">
<p i18n="transponderInformation"></p>
</div>
</div>
</div>
<div class="content_toolbar require-transponder-supported">
<div class="btn save_btn">
<a class="save" href="#" i18n="transponderButtonSave"></a>
</div>
</div>
</div>

View file

@ -1,101 +0,0 @@
'use strict';
TABS.transponder = {
available: false
};
TABS.transponder.initialize = function (callback, scrollPosition) {
var self = this;
if (GUI.active_tab != 'transponder') {
GUI.active_tab = 'transponder';
googleAnalytics.sendAppView('Transponder');
}
// transponder supported added in MSP API Version 1.16.0
TABS.transponder.available = semver.gte(CONFIG.apiVersion, "1.16.0");
if (!TABS.transponder.available) {
load_html();
return;
}
function load_html() {
GUI.load("./tabs/transponder.html", process_html);
}
// get the transponder data and a flag to see if transponder support is enabled on the FC
MSP.send_message(MSPCodes.MSP_TRANSPONDER_CONFIG, false, false, load_html);
// Convert a hex string to a byte array
function hexToBytes(hex) {
for (var bytes = [], c = 0; c < hex.length; c += 2)
bytes.push(~parseInt(hex.substr(c, 2), 16));
return bytes;
}
function pad(n, width) {
n = n + '';
return n.length >= width ? n : new Array(width - n.length + 1).join('0') + n;
}
// Convert a byte array to a hex string
function bytesToHex(bytes) {
for (var hex = [], i = 0; i < bytes.length; i++) {
hex.push(pad(((~bytes[i]) & 0xFF).toString(16),2));
}
return hex.join("").toUpperCase();
}
function process_html() {
// translate to user-selected language
localize();
$(".tab-transponder")
.toggleClass("transponder-supported", TABS.transponder.available && TRANSPONDER.supported);
if (TABS.transponder.available) {
var data = bytesToHex(TRANSPONDER.data);
$('input[name="data"]').val(data);
$('input[name="data"]').prop('maxLength', data.length);
$('a.save').click(function () {
// gather data that doesn't have automatic change event bound
var dataString = $('input[name="data"]').val();
var expectedLength = TRANSPONDER.data.length;
var hexRegExp = new RegExp('[0-9a-fA-F]{' + (expectedLength * 2) + '}', 'gi');
if (!dataString.match(hexRegExp)) {
GUI.log(chrome.i18n.getMessage('transponderDataInvalid'));
return;
}
TRANSPONDER.data = hexToBytes(dataString);
//
// send data to FC
//
function save_transponder_config() {
MSP.send_message(MSPCodes.MSP_SET_TRANSPONDER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_TRANSPONDER_CONFIG), false, save_to_eeprom);
}
function save_to_eeprom() {
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
GUI.log(chrome.i18n.getMessage('transponderEepromSaved'));
});
}
save_transponder_config();
});
}
GUI.content_ready(callback);
}
};
TABS.transponder.cleanup = function (callback) {
if (callback) callback();
};