1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-15 04:15:28 +03:00

Merge branch 'master' into MrD-Add-switch-indicators-to-OSD

This commit is contained in:
Darren Lines 2022-02-24 17:32:04 +00:00
commit 27d1897c24
41 changed files with 1033 additions and 824 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. 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? ## 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. 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. 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 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 ## Building and running INAV Configurator locally (for development or Linux users)
**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)
For local development, **node.js** build system is used. For local development, **node.js** build system is used.
@ -70,6 +78,12 @@ for the Windows app. If you don't have Wine installed you can create a release b
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 ## Different map providers
INAV Configurator 2.1 allows to choose between OpenStreetMap, Bing Maps, and MapProxy map providers. INAV Configurator 2.1 allows to choose between OpenStreetMap, Bing Maps, and MapProxy 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. Enter MapProxy service layer (inav_layer if configured from MAPPROXY.md)
1. Once completed, you can zoom in on area you will be flying in while connected to the internet in either GPS or Mission Control tab to save the cache for offline use 1. Once completed, you can zoom in on 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 ## Notes
### WebGL ### 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 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 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 ## Issue trackers
For INAV configurator issues raise them here For INAV configurator issues raise them here
@ -144,8 +141,3 @@ https://github.com/iNavFlight/inav/issues
## Developers ## Developers
We accept clean and reasonable patches, submit them! 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

@ -871,79 +871,79 @@
"message": "Fixed Wing Auto Launch Settings" "message": "Fixed Wing Auto Launch Settings"
}, },
"configurationLaunchVelocity": { "configurationLaunchVelocity": {
"message": "Threshold Velocity [cm/s]" "message": "Threshold Velocity"
}, },
"configurationLaunchVelocityHelp": { "configurationLaunchVelocityHelp": {
"message": "Forward velocity threshold for swing-launch detection. Default: 300 [100-10000]" "message": "Forward velocity threshold for swing-launch detection. Default: 300 [100-10000]"
}, },
"configurationLaunchAccel": { "configurationLaunchAccel": {
"message": "Threshold Acceleration [cm/s/s]" "message": "Threshold Acceleration"
}, },
"configurationLaunchAccelHelp": { "configurationLaunchAccelHelp": {
"message": "Forward acceleration threshold for bungee launch or throw launch, 1G = 981 cm/s/s. Default: 1863 [1000-20000]" "message": "Forward acceleration threshold for bungee launch or throw launch, 1G = 981 cm/s/s. Default: 1863 [1000-20000]"
}, },
"configurationLaunchMaxAngle": { "configurationLaunchMaxAngle": {
"message": "Max Throw Angle [°]" "message": "Max Throw Angle"
}, },
"configurationLaunchMaxAngleHelp": { "configurationLaunchMaxAngleHelp": {
"message": "Max throw angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely. Default: 45 [5-180]" "message": "Max throw angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely. Default: 45 [5-180]"
}, },
"configurationLaunchDetectTime": { "configurationLaunchDetectTime": {
"message": "Detect Time [ms]" "message": "Detect Time"
}, },
"configurationLaunchDetectTimeHelp": { "configurationLaunchDetectTimeHelp": {
"message": "Time for which thresholds have to breached to consider launch happened. Default: 40 [10-1000]" "message": "Time for which thresholds have to breached to consider launch happened. Default: 40 [10-1000]"
}, },
"configurationLaunchThr": { "configurationLaunchThr": {
"message": "Launch Throttle [uS]" "message": "Launch Throttle"
}, },
"configurationLaunchThrHelp": { "configurationLaunchThrHelp": {
"message": "Launch throttle - throttle to be set during launch sequence. Default: 1700 [1000-2000]" "message": "Launch throttle - throttle to be set during launch sequence. Default: 1700 [1000-2000]"
}, },
"configurationLaunchIdleThr": { "configurationLaunchIdleThr": {
"message": "Idle Throttle [uS]" "message": "Idle Throttle"
}, },
"configurationLaunchIdleThrHelp": { "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]" "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": { "configurationLaunchMotorDelay": {
"message": "Motor Delay [ms]" "message": "Motor Delay"
}, },
"configurationLaunchMotorDelayHelp": { "configurationLaunchMotorDelayHelp": {
"message": "Delay between detected launch and launch sequence start and throttling up. Default: 500 [0-5000]" "message": "Delay between detected launch and launch sequence start and throttling up. Default: 500 [0-5000]"
}, },
"configurationLaunchSpinupTime": { "configurationLaunchSpinupTime": {
"message": "Motor Spinup Time [ms]" "message": "Motor Spinup Time"
}, },
"configurationLaunchSpinupTimeHelp": { "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]" "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": { "configurationLaunchMinTime": {
"message": "Minimum Launch Time [ms]" "message": "Minimum Launch Time"
}, },
"configurationLaunchMinTimeHelp": { "configurationLaunchMinTimeHelp": {
"message": "Allow launch mode to execute at least this time [ms] and ignore stick movements. Default: 0 [0-60000]" "message": "Allow launch mode to execute at least this time [ms] and ignore stick movements. Default: 0 [0-60000]"
}, },
"configurationLaunchTimeout": { "configurationLaunchTimeout": {
"message": "Launch Timeout [ms]" "message": "Launch Timeout"
}, },
"configurationLaunchTimeoutHelp": { "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]" "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": { "configurationLaunchEndTime": {
"message": "End Transition Time [ms]" "message": "End Transition Time"
}, },
"configurationLaunchEndTimeHelp": { "configurationLaunchEndTimeHelp": {
"message": "Smooth transition time at the end of the launch (ms). This is added to the Launch Timeout. Default: 2000 [0-5000]" "message": "Smooth transition time at the end of the launch (ms). This is added to the Launch Timeout. Default: 2000 [0-5000]"
}, },
"configurationLaunchMaxAltitude": { "configurationLaunchMaxAltitude": {
"message": "Maximum Altitude [cm]" "message": "Maximum Altitude"
}, },
"configurationLaunchMaxAltitudeHelp": { "configurationLaunchMaxAltitudeHelp": {
"message": "Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. Default: 0 [0-60000]" "message": "Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. Default: 0 [0-60000]"
}, },
"configurationLaunchClimbAngle": { "configurationLaunchClimbAngle": {
"message": "Climb Angle [°]" "message": "Climb Angle"
}, },
"configurationLaunchClimbAngleHelp": { "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]" "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]"
@ -973,7 +973,7 @@
"message": "Cycles/Sec (Hz)" "message": "Cycles/Sec (Hz)"
}, },
"configurationGPS": { "configurationGPS": {
"message": "GPS" "message": "Configuration"
}, },
"configurationGPSProtocol": { "configurationGPSProtocol": {
"message": "Protocol" "message": "Protocol"
@ -1624,10 +1624,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>" "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": { "gpsHead": {
"message": "GPS" "message": "Position"
}, },
"gpsStatHead": { "gpsStatHead": {
"message": "GPS Statistics" "message": "Statistics"
}, },
"gpsMapHead": { "gpsMapHead": {
"message": "Current GPS location" "message": "Current GPS location"
@ -2126,7 +2126,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)." "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": { "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": { "failsafeDelayHelp": {
"message": "Time for stage 1 to wait for recovery" "message": "Time for stage 1 to wait for recovery"
@ -2135,7 +2135,7 @@
"message": "Throttle value used while landing" "message": "Throttle value used while landing"
}, },
"failsafeOffDelayItem": { "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": { "failsafeOffDelayHelp": {
"message": "Time to stay in landing mode untill the motors are turned off and the craft is disarmed" "message": "Time to stay in landing mode untill the motors are turned off and the craft is disarmed"
@ -2510,16 +2510,16 @@
"message": "User Control Mode" "message": "User Control Mode"
}, },
"posholdDefaultSpeed": { "posholdDefaultSpeed": {
"message": "Default navigation speed [cm/s]" "message": "Default navigation speed"
}, },
"posholdDefaultSpeedHelp": { "posholdDefaultSpeedHelp": {
"message": "Default speed during RTH, also used for WP navigation if no speed set for WP leg. Limited to Max. navigation speed" "message": "Default speed during RTH, also used for WP navigation if no speed set for WP leg. Limited to Max. navigation speed"
}, },
"posholdMaxSpeed": { "posholdMaxSpeed": {
"message": "Max. navigation speed [cm/s]" "message": "Max. navigation speed"
}, },
"posholdMaxManualSpeed": { "posholdMaxManualSpeed": {
"message": "Max. CRUISE speed [cm/s]" "message": "Max. CRUISE speed"
}, },
"posholdMaxManualSpeedHelp": { "posholdMaxManualSpeedHelp": {
"message": "Maximum horizonal velocity allowed for pilot manual control during POSHOLD/CRUISE mode" "message": "Maximum horizonal velocity allowed for pilot manual control during POSHOLD/CRUISE mode"
@ -2531,7 +2531,7 @@
"message": "Max. ALTHOLD climb rate [cm/s]" "message": "Max. ALTHOLD climb rate [cm/s]"
}, },
"posholdMaxBankAngle": { "posholdMaxBankAngle": {
"message": "Multirotor max. banking angle [degrees]" "message": "Multirotor max. banking angle"
}, },
"posholdMaxBankAngleHelp": { "posholdMaxBankAngleHelp": {
"message": "Maximum banking angle in navigation modes. Constrained by maximum ROLL angle in PID tuning tab." "message": "Maximum banking angle in navigation modes. Constrained by maximum ROLL angle in PID tuning tab."
@ -2588,7 +2588,7 @@
"message": "Automatic landing settings" "message": "Automatic landing settings"
}, },
"minRthDistance": { "minRthDistance": {
"message": "Min. RTH distance [cm]" "message": "Min. RTH distance"
}, },
"minRthDistanceHelp": { "minRthDistanceHelp": {
"message": "If UAV is within this distance from the home point, it will land instead of RTH then land" "message": "If UAV is within this distance from the home point, it will land instead of RTH then land"
@ -2618,19 +2618,19 @@
"message": "RTH altitude mode" "message": "RTH altitude mode"
}, },
"rthAbortThreshold": { "rthAbortThreshold": {
"message": "RTH abort threshold [cm]" "message": "RTH abort threshold"
}, },
"rthAbortThresholdHelp": { "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." "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": { "rthAltitude": {
"message": "RTH altitude [cm]" "message": "RTH altitude"
}, },
"rthAltitudeHelp": { "rthAltitudeHelp": {
"message": "Used in Extra, Fixed and 'At Least' RTH altitude modes" "message": "Used in Extra, Fixed and 'At Least' RTH altitude modes"
}, },
"rthHomeAltitudeLabel": { "rthHomeAltitudeLabel": {
"message": "RTH Home altitude [cm]" "message": "RTH Home altitude"
}, },
"rthHomeAltitudeHelp": { "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." "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."
@ -2657,7 +2657,7 @@
"message": "<strong>Final approach altitude</strong>. Altitude under which the aircraft will go down at <strong>Final landing speed</strong> until touchdown" "message": "<strong>Final approach altitude</strong>. Altitude under which the aircraft will go down at <strong>Final landing speed</strong> until touchdown"
}, },
"emergencyDescentRate": { "emergencyDescentRate": {
"message": "Emergency landing speed [cm/s]" "message": "Emergency landing speed"
}, },
"cruiseThrottle": { "cruiseThrottle": {
"message": "Cruise throttle" "message": "Cruise throttle"
@ -2681,31 +2681,31 @@
"message": "Max. throttle" "message": "Max. throttle"
}, },
"maxBankAngle": { "maxBankAngle": {
"message": "Max. navigation bank angle [degrees]" "message": "Max. navigation bank angle"
}, },
"maxBankAngleHelp": { "maxBankAngleHelp": {
"message": "Maximum banking angle in navigation modes. Constrained by maximum ROLL angle in PID tuning tab." "message": "Maximum banking angle in navigation modes. Constrained by maximum ROLL angle in PID tuning tab."
}, },
"maxClimbAngle": { "maxClimbAngle": {
"message": "Max. navigation climb angle [degrees]" "message": "Max. navigation climb angle"
}, },
"maxClimbAngleHelp": { "maxClimbAngleHelp": {
"message": "Maximum climb angle in navigation modes. Constrained by maximum PITCH angle in PID tuning tab." "message": "Maximum climb angle in navigation modes. Constrained by maximum PITCH angle in PID tuning tab."
}, },
"navManualClimbRate": { "navManualClimbRate": {
"message": "Max. Alt-hold climb rate [cm/s]" "message": "Max. Alt-hold climb rate"
}, },
"navManualClimbRateHelp": { "navManualClimbRateHelp": {
"message": "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" "message": "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
}, },
"navAutoClimbRate": { "navAutoClimbRate": {
"message": "Max. navigation climb rate [cm/s]" "message": "Max. navigation climb rate"
}, },
"navAutoClimbRateHelp": { "navAutoClimbRateHelp": {
"message": "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" "message": "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
}, },
"maxDiveAngle": { "maxDiveAngle": {
"message": "Max. navigation dive angle [degrees]" "message": "Max. navigation dive angle"
}, },
"maxDiveAngleHelp": { "maxDiveAngleHelp": {
"message": "Maximum dive angle in navigation modes. Constrained by maximum PITCH angle in PID tuning tab." "message": "Maximum dive angle in navigation modes. Constrained by maximum PITCH angle in PID tuning tab."
@ -2723,13 +2723,13 @@
"message": "How smoothly the autopilot adjusts the throttle level in response to pitch angle changes [0-9]." "message": "How smoothly the autopilot adjusts the throttle level in response to pitch angle changes [0-9]."
}, },
"pitchToThrottleThreshold": { "pitchToThrottleThreshold": {
"message": "Instantaneous throttle adjustment threshold [centidegrees]" "message": "Instantaneous throttle adjustment threshold"
}, },
"pitchToThrottleThresholdHelp": { "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." "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": { "loiterRadius": {
"message": "Loiter radius [cm]" "message": "Loiter radius"
}, },
"loiterDirectionLabel": { "loiterDirectionLabel": {
"message": "Loiter direction" "message": "Loiter direction"
@ -2747,25 +2747,25 @@
"message": "Battery Estimation Settings" "message": "Battery Estimation Settings"
}, },
"idlePower": { "idlePower": {
"message": "Idle power [cW]" "message": "Idle power"
}, },
"idlePowerHelp": { "idlePowerHelp": {
"message": "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" "message": "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
}, },
"cruisePower": { "cruisePower": {
"message": "Cruise power [cW]" "message": "Cruise power"
}, },
"cruisePowerHelp": { "cruisePowerHelp": {
"message": "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" "message": "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
}, },
"cruiseSpeed": { "cruiseSpeed": {
"message": "Cruise speed [cm/s]" "message": "Cruise speed"
}, },
"cruiseSpeedHelp": { "cruiseSpeedHelp": {
"message": "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" "message": "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
}, },
"rthEnergyMargin": { "rthEnergyMargin": {
"message": "RTH energy margin [%]" "message": "RTH energy margin"
}, },
"rthEnergyMarginHelp": { "rthEnergyMarginHelp": {
"message": "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation." "message": "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation."
@ -2777,13 +2777,13 @@
"message": "Waypoint Navigation Settings" "message": "Waypoint Navigation Settings"
}, },
"waypointRadius": { "waypointRadius": {
"message": "Waypoint radius [cm]" "message": "Waypoint radius"
}, },
"waypointRadiusHelp": { "waypointRadiusHelp": {
"message": "This sets the distance away from a waypoint that triggers the waypoint as reached." "message": "This sets the distance away from a waypoint that triggers the waypoint as reached."
}, },
"waypointSafeDistance": { "waypointSafeDistance": {
"message": "Waypoint safe distance [cm]." "message": "Waypoint safe distance"
}, },
"waypointSafeDistanceHelp": { "waypointSafeDistanceHelp": {
"message": "The maximum distance between the home point and the first waypoint." "message": "The maximum distance between the home point and the first waypoint."
@ -2894,16 +2894,16 @@
"message": "Fly Time (minutes)" "message": "Fly Time (minutes)"
}, },
"osd_alt_alarm": { "osd_alt_alarm": {
"message": "Altitude (meters)" "message": "Altitude"
}, },
"osd_dist_alarm": { "osd_dist_alarm": {
"message": "Distance (meters)" "message": "Distance"
}, },
"osdAlarmDIST_HELP": { "osdAlarmDIST_HELP": {
"message": "The distance to home indicator will flash when the distance is greater than this value. Zero disables this alarm." "message": "The distance to home indicator will flash when the distance is greater than this value. Zero disables this alarm."
}, },
"osd_neg_alt_alarm": { "osd_neg_alt_alarm": {
"message": "Negative Altitude (meters)" "message": "Negative Altitude"
}, },
"osdAlarmMAX_NEG_ALTITUDE_HELP": { "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." "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."
@ -3710,49 +3710,49 @@
"message": "Distance to home" "message": "Distance to home"
}, },
"brakingSpeedThreshold": { "brakingSpeedThreshold": {
"message": "Min. speed threshold [cm/s]" "message": "Min. speed threshold"
}, },
"brakingSpeedThresholdTip": { "brakingSpeedThresholdTip": {
"message": "Braking will be enabled only if actual speed if higher than threshold" "message": "Braking will be enabled only if actual speed if higher than threshold"
}, },
"brakingDisengageSpeed": { "brakingDisengageSpeed": {
"message": "Braking disengage speed [cm/s]" "message": "Braking disengage speed"
}, },
"brakingDisengageSpeedTip": { "brakingDisengageSpeedTip": {
"message": "Braking will end when speed goes below this value" "message": "Braking will end when speed goes below this value"
}, },
"brakingTimeout": { "brakingTimeout": {
"message": "Max. braking duration [ms]" "message": "Max. braking duration"
}, },
"brakingTimeoutTip": { "brakingTimeoutTip": {
"message": "Safety measure. This is the longest period of time braking can be active." "message": "Safety measure. This is the longest period of time braking can be active."
}, },
"brakingBoostFactor": { "brakingBoostFactor": {
"message": "Boost factor [%]" "message": "Boost factor"
}, },
"brakingBoostFactorTip": { "brakingBoostFactorTip": {
"message": "Defines how strong the braking boost will be. 100% means the navigation engine is allowed to double the banking speed and acceleration" "message": "Defines how strong the braking boost will be. 100% means the navigation engine is allowed to double the banking speed and acceleration"
}, },
"brakingBoostTimeout": { "brakingBoostTimeout": {
"message": "Max. braking boost duration [ms]" "message": "Max. braking boost duration"
}, },
"brakingBoostTimeoutTip": { "brakingBoostTimeoutTip": {
"message": "Safety measure. This is the longest period of time braking boost can be active." "message": "Safety measure. This is the longest period of time braking boost can be active."
}, },
"brakingBoostSpeedThreshold": { "brakingBoostSpeedThreshold": {
"message": "Boost min. speed threshold [cm/s]" "message": "Boost min. speed threshold"
}, },
"brakingBoostSpeedThresholdTip": { "brakingBoostSpeedThresholdTip": {
"message": "Braking boost will be enabled only if actual speed if higher than threshold" "message": "Braking boost will be enabled only if actual speed if higher than threshold"
}, },
"brakingBoostDisengageSpeed": { "brakingBoostDisengageSpeed": {
"message": "Braking boost disengage speed [cm/s]" "message": "Braking boost disengage speed"
}, },
"brakingBoostDisengageSpeedTip": { "brakingBoostDisengageSpeedTip": {
"message": "Braking boost will end when speed goes below this value" "message": "Braking boost will end when speed goes below this value"
}, },
"brakingBankAngle": { "brakingBankAngle": {
"message": "Max. bank angle [degrees]" "message": "Max. bank angle"
}, },
"brakingBankAngleTip": { "brakingBankAngleTip": {
"message": "Max bank angle allowed during braking phase" "message": "Max bank angle allowed during braking phase"

View file

@ -1,4 +1,4 @@
/*global mspHelper,$,GUI,MSP,BF_CONFIG,chrome*/ /*global mspHelper,$,GUI,MSP,chrome*/
'use strict'; 'use strict';
var helper = helper || {}; var helper = helper || {};
@ -733,7 +733,7 @@ helper.defaultsDialog = (function () {
savingDefaultsModal.close(); savingDefaultsModal.close();
} }
mspHelper.loadBfConfig(function () { mspHelper.loadFeatures(function () {
privateScope.setFeaturesBits(selectedDefaultPreset) privateScope.setFeaturesBits(selectedDefaultPreset)
}); });
} else { } else {

View file

@ -2,7 +2,6 @@
// define all the global variables that are uses to hold FC state // define all the global variables that are uses to hold FC state
var CONFIG, var CONFIG,
BF_CONFIG,
LED_STRIP, LED_STRIP,
LED_COLORS, LED_COLORS,
LED_MODE_COLORS, LED_MODE_COLORS,
@ -63,7 +62,10 @@ var CONFIG,
OUTPUT_MAPPING, OUTPUT_MAPPING,
SETTINGS, SETTINGS,
BRAKING_CONFIG, BRAKING_CONFIG,
SAFEHOMES; SAFEHOMES,
BOARD_ALIGNMENT,
CURRENT_METER_CONFIG,
FEATURES;
var FC = { var FC = {
MAX_SERVO_RATE: 125, MAX_SERVO_RATE: 125,
@ -127,21 +129,25 @@ var FC = {
name: '' name: ''
}; };
BF_CONFIG = { BOARD_ALIGNMENT = {
mixerConfiguration: 0, roll: 0,
features: 0, pitch: 0,
serialrx_type: 0, yaw: 0
board_align_roll: 0, };
board_align_pitch: 0,
board_align_yaw: 0, CURRENT_METER_CONFIG = {
currentscale: 0, scale: 0,
currentoffset: 0 offset: 0,
type: 0,
capacity: 0
}; };
LED_STRIP = []; LED_STRIP = [];
LED_COLORS = []; LED_COLORS = [];
LED_MODE_COLORS = []; LED_MODE_COLORS = [];
FEATURES = 0;
PID = { PID = {
}; };
@ -576,7 +582,7 @@ var FC = {
{bit: 1, group: 'batteryVoltage', name: 'VBAT'}, {bit: 1, group: 'batteryVoltage', name: 'VBAT'},
{bit: 4, group: 'other', name: 'MOTOR_STOP'}, {bit: 4, group: 'other', name: 'MOTOR_STOP'},
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true}, {bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
{bit: 7, group: 'gps', name: 'GPS', haveTip: true}, {bit: 7, group: 'other', name: 'GPS', haveTip: true},
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true}, {bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'}, {bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'},
{bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true}, {bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true},
@ -606,7 +612,7 @@ var FC = {
features = this.getFeatures(); features = this.getFeatures();
} }
for (var i = 0; i < features.length; i++) { 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; return true;
} }
} }

View file

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

View file

@ -44,6 +44,7 @@ const
// generate mixer // generate mixer
const mixerList = [ const mixerList = [
// ** Multirotor
{ {
id: 1, id: 1,
name: 'Tricopter', name: 'Tricopter',
@ -104,17 +105,6 @@ const mixerList = [
motorMixer: [], motorMixer: [],
servoMixer: [] servoMixer: []
}, // 4 }, // 4
{
id: 5,
name: 'Gimbal',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 5
{ {
id: 6, id: 6,
name: 'Y6', name: 'Y6',
@ -151,44 +141,6 @@ const mixerList = [
], ],
servoMixer: [] servoMixer: []
}, // 7 }, // 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
{ {
id: 9, id: 9,
name: 'Y4', name: 'Y4',
@ -283,50 +235,6 @@ const mixerList = [
], ],
servoMixer: [] servoMixer: []
}, // 13 }, // 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
{ {
id: 17, id: 17,
name: 'V-tail Quad', name: 'V-tail Quad',
@ -361,17 +269,6 @@ const mixerList = [
], ],
servoMixer: [] servoMixer: []
}, // 18 }, // 18
{
id: 19,
name: 'PPM to SERVO',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 19
{ {
id: 20, id: 20,
name: 'Dualcopter', name: 'Dualcopter',
@ -421,17 +318,6 @@ const mixerList = [
motorMixer: [], motorMixer: [],
servoMixer: [] servoMixer: []
}, // 23 }, // 23
{
id: 24,
name: 'Custom Airplane',
model: 'twin_plane',
image: 'airplane',
enabled: false,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [],
servoMixer: []
}, // 24
{ {
id: 25, id: 25,
name: 'Custom Tricopter', name: 'Custom Tricopter',
@ -443,6 +329,66 @@ const mixerList = [
motorMixer: [], motorMixer: [],
servoMixer: [] servoMixer: []
}, // 25 }, // 25
// ** Fixed Wing **
{
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),
],
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
{
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),
],
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, id: 26,
name: 'Airplane with differential thrust', name: 'Airplane with differential thrust',
@ -464,10 +410,10 @@ const mixerList = [
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/ /*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0), new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
] ]
}, }, // 26
{ {
id: 28, id: 28,
name: 'Airplane V-tail (individual aileron servos)', name: 'Airplane V-tail',
model: 'vtail_plane', model: 'vtail_plane',
image: 'airplane_vtail', image: 'airplane_vtail',
enabled: true, enabled: true,
@ -487,7 +433,31 @@ const mixerList = [
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0), new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_YAW, -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',
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, id: 29,
name: 'Airplane V-tail (single aileron servo)', name: 'Airplane V-tail (single aileron servo)',
@ -506,7 +476,7 @@ const mixerList = [
new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0), new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0), new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
] ]
}, }, //29
{ {
id: 30, id: 30,
name: 'Airplane without rudder', name: 'Airplane without rudder',
@ -526,7 +496,44 @@ const mixerList = [
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 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_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0),*/
] ]
}, }, // 30
{
id: 24,
name: 'Custom Airplane',
model: 'twin_plane',
image: 'airplane',
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, id: 31,
name: 'Rover', name: 'Rover',
@ -556,8 +563,8 @@ const mixerList = [
servoMixer: [ servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0), new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
] ]
} },
, // ** Misc **
{ {
id: 33, id: 33,
name: 'Other', name: 'Other',
@ -572,7 +579,29 @@ const mixerList = [
servoMixer: [ servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0), 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 = [ const platformList = [

View file

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

View file

@ -72,7 +72,7 @@ var MSP = {
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order 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 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 ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
last_received_timestamp: null, last_received_timestamp: null,

View file

@ -33,6 +33,12 @@ var MSPCodes = {
MSP_SET_CHANNEL_FORWARDING: 33, MSP_SET_CHANNEL_FORWARDING: 33,
MSP_MODE_RANGES: 34, MSP_MODE_RANGES: 34,
MSP_SET_MODE_RANGE: 35, 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_RX_CONFIG: 44,
MSP_SET_RX_CONFIG: 45, MSP_SET_RX_CONFIG: 45,
MSP_LED_COLORS: 46, MSP_LED_COLORS: 46,
@ -44,8 +50,6 @@ var MSPCodes = {
MSP_CF_SERIAL_CONFIG: 54, MSP_CF_SERIAL_CONFIG: 54,
MSP_SET_CF_SERIAL_CONFIG: 55, MSP_SET_CF_SERIAL_CONFIG: 55,
MSP_SONAR: 58, MSP_SONAR: 58,
MSP_PID_CONTROLLER: 59,
MSP_SET_PID_CONTROLLER: 60,
MSP_ARMING_CONFIG: 61, MSP_ARMING_CONFIG: 61,
MSP_SET_ARMING_CONFIG: 62, MSP_SET_ARMING_CONFIG: 62,
MSP_DATAFLASH_SUMMARY: 70, MSP_DATAFLASH_SUMMARY: 70,
@ -149,10 +153,10 @@ var MSPCodes = {
// Additional private MSP for baseflight configurator (yes thats us \o/) // Additional private MSP for baseflight configurator (yes thats us \o/)
MSP_RX_MAP: 64, // get channel map (also returns number of channels total) 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_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_BF_CONFIG: 66, // Depreciated
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save MSP_SET_BF_CONFIG: 67, // Depreciated
MSP_SET_REBOOT: 68, // reboot settings 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 // INAV specific codes
MSPV2_SETTING: 0x1003, MSPV2_SETTING: 0x1003,

View file

@ -68,15 +68,6 @@ var mspHelper = (function (gui) {
colorCount, colorCount,
color; color;
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) { 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: case MSPCodes.MSP_STATUS:
console.log('Using deprecated msp command: MSP_STATUS'); console.log('Using deprecated msp command: MSP_STATUS');
CONFIG.cycleTime = data.getUint16(0, true); CONFIG.cycleTime = data.getUint16(0, true);
@ -293,14 +284,6 @@ var mspHelper = (function (gui) {
RC_tuning.manual_pitch_rate = data.getUint8(offset++); RC_tuning.manual_pitch_rate = data.getUint8(offset++);
RC_tuning.manual_yaw_rate = data.getUint8(offset++); RC_tuning.manual_yaw_rate = data.getUint8(offset++);
break; 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: case MSPCodes.MSP2_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array // 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) { for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
@ -640,9 +623,6 @@ var mspHelper = (function (gui) {
break; break;
case MSPCodes.MSP_SET_RAW_GPS: case MSPCodes.MSP_SET_RAW_GPS:
break; break;
case MSPCodes.MSP_SET_PID:
console.log('PID settings saved');
break;
case MSPCodes.MSP2_SET_PID: case MSPCodes.MSP2_SET_PID:
console.log('PID settings saved'); console.log('PID settings saved');
break; break;
@ -734,19 +714,36 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_SET_RX_MAP: case MSPCodes.MSP_SET_RX_MAP:
console.log('RCMAP saved'); console.log('RCMAP saved');
break; break;
case MSPCodes.MSP_BF_CONFIG:
BF_CONFIG.mixerConfiguration = data.getUint8(0); case MSPCodes.MSP_BOARD_ALIGNMENT:
BF_CONFIG.features = data.getUint32(1, true); BOARD_ALIGNMENT.roll = data.getInt16(0, true); // -180 - 360
BF_CONFIG.serialrx_type = data.getUint8(5); BOARD_ALIGNMENT.pitch = data.getInt16(2, true); // -180 - 360
BF_CONFIG.board_align_roll = data.getInt16(6, true); // -180 - 360 BOARD_ALIGNMENT.yaw = data.getInt16(4, 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);
break; 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; 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: case MSPCodes.MSP_SET_REBOOT:
console.log('Reboot request accepted'); console.log('Reboot request accepted');
break; break;
@ -800,28 +797,6 @@ var mspHelper = (function (gui) {
console.log('Channel forwarding saved'); console.log('Channel forwarding saved');
break; 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: case MSPCodes.MSP2_CF_SERIAL_CONFIG:
SERIAL_CONFIG.ports = []; SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 4 + 4; var bytesPerPort = 1 + 4 + 4;
@ -844,7 +819,6 @@ var mspHelper = (function (gui) {
} }
break; break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG: case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
console.log('Serial config saved'); console.log('Serial config saved');
break; break;
@ -1559,24 +1533,33 @@ var mspHelper = (function (gui) {
i; i;
switch (code) { switch (code) {
case MSPCodes.MSP_SET_BF_CONFIG:
buffer.push(BF_CONFIG.mixerConfiguration); case MSPCodes.MSP_SET_FEATURE:
buffer.push(specificByte(BF_CONFIG.features, 0)); buffer.push(specificByte(FEATURES, 0));
buffer.push(specificByte(BF_CONFIG.features, 1)); buffer.push(specificByte(FEATURES, 1));
buffer.push(specificByte(BF_CONFIG.features, 2)); buffer.push(specificByte(FEATURES, 2));
buffer.push(specificByte(BF_CONFIG.features, 3)); buffer.push(specificByte(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));
break; 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: case MSPCodes.MSP_SET_VTX_CONFIG:
if (VTX_CONFIG.band > 0) { if (VTX_CONFIG.band > 0) {
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1)); buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
@ -1589,13 +1572,6 @@ var mspHelper = (function (gui) {
buffer.push(0); buffer.push(0);
buffer.push(VTX_CONFIG.low_power_disarm); buffer.push(VTX_CONFIG.low_power_disarm);
break; 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: case MSPCodes.MSP2_SET_PID:
for (i = 0; i < PIDs.length; i++) { for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0])); buffer.push(parseInt(PIDs[i][0]));
@ -1812,24 +1788,6 @@ var mspHelper = (function (gui) {
} }
break; 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: case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) { for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i]; var serialPort = SERIAL_CONFIG.ports[i];
@ -2665,7 +2623,7 @@ var mspHelper = (function (gui) {
/* /*
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order 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 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 ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
*/ */
@ -2752,14 +2710,6 @@ var mspHelper = (function (gui) {
* Basic sending methods used for chaining purposes * 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) { self.loadINAVPidConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback); MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
}; };
@ -2800,8 +2750,16 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback); MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
}; };
self.loadBfConfig = function (callback) { self.loadFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, callback); MSP.send_message(MSPCodes.MSP_FEATURE, 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) { self.queryFcStatus = function (callback) {
@ -2904,8 +2862,16 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback); MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback);
}; };
self.saveBfConfig = function (callback) { self.saveFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, 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) { self.saveMisc = function (callback) {

View file

@ -99,5 +99,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; return self;
}; };

View file

@ -28,6 +28,8 @@ var Settings = (function () {
} }
parent.show(); parent.show();
input.prop('title', 'CLI: ' + input.data('setting'));
if (input.prop('tagName') == 'SELECT' || s.setting.table) { if (input.prop('tagName') == 'SELECT' || s.setting.table) {
if (input.attr('type') == 'checkbox') { if (input.attr('type') == 'checkbox') {
input.prop('checked', s.value > 0); input.prop('checked', s.value > 0);
@ -70,9 +72,9 @@ var Settings = (function () {
input.val(s.value.toFixed(2)); input.val(s.value.toFixed(2));
} else { } else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1); var multiplier = parseFloat(input.data('setting-multiplier') || 1);
input.attr('type', 'number');
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
input.attr('type', 'number');
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) { if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier))); input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier)));
} }
@ -113,19 +115,19 @@ var Settings = (function () {
const getUnitDisplayTypeValue = () => { const getUnitDisplayTypeValue = () => {
// Try and match the values // Try and match the values
switch (configUnitType) { switch (configUnitType) {
case UnitType.imperial:
return 0;
break;
case UnitType.metric:
return 1;
break;
case UnitType.OSD: // Match the OSD value on the UI case UnitType.OSD: // Match the OSD value on the UI
return globalSettings.osdUnits; return globalSettings.osdUnits;
break; break;
case UnitType.imperial:
return 0; // Imperial OSD Value
break;
case UnitType.metric:
return 1; // Metric + MPH OSD Value
break;
case UnitType.none: case UnitType.none:
default: default:
// Something went wrong
return -1; return -1;
break;
} }
} }
@ -135,67 +137,199 @@ var Settings = (function () {
const oldValue = element.val(); 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;',
// 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 // Ensure we can do conversions
if (configUnitType === UnitType.none || uiUnitValue === -1 || !inputUnit || !oldValue || !element) { if (!inputUnit || !oldValue || !element) {
return; return;
} }
// Used to convert between a value and a value matching the int //this is used to get the factor in which we multiply
// unit display value. Eg 1 = Metric //to get the correct conversion, the first index is the from
// units. We use the OSD unit values here for easy //unit and the second is the too unit
//unitConversionTable[toUnit][fromUnit] -> factor
const unitRatioTable = {
'cm' : {
'm' : 100,
'ft' : 30.48
},
'm' : {
'm' : 1,
'ft' : 0.3048
},
'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
},
'decidegc' : {
'degc' : 10,
'degf' : 'FAHREN'
},
};
//this holds which units get converted in which unit systems
const conversionTable = { const conversionTable = {
1: { 0: { //imperial
'cm': { multiplier: 100, unitName: 'm' }, 'cm' : 'ft',
'cms': { multiplier: 27.77777777777778, unitName: 'Km/h' } 'm' : 'ft',
'm-lrg' : 'mi',
'cms' : 'mph',
'v-cms' : 'fts',
'msec' : 'sec',
'dsec' : 'sec',
'decideg' : 'deg',
'decidegc' : 'degf',
}, },
2: { 1: { //metric
'cm': { multiplier: 100, unitName: 'm' }, 'cm': 'm',
'm' : 'm',
'm-lrg' : 'km',
'cms' : 'kmh',
'v-cms' : 'ms',
'msec' : 'sec',
'dsec' : 'sec',
'decideg' : 'deg',
'decidegc' : 'degc',
}, },
4: { 2: { //metric with MPH
'cms': { multiplier: 51.44444444444457, unitName: 'Kt' } 'cm': 'm',
'm' : 'm',
'm-lrg' : 'km',
'cms' : 'mph',
'v-cms' : 'ms',
'decideg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
}, },
default: { 3:{ //UK
'cm': { multiplier: 30.48, unitName: 'ft' }, 'cm' : 'ft',
'cms': { multiplier: 44.704, unitName: 'mph' }, 'm' : 'ft',
'ms': { multiplier: 1000, unitName: 'sec' } 'm-lrg' : 'mi',
'cms' : 'mph',
'v-cms' : 'fts',
'decideg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
}, },
} 4: { //General aviation
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'nm',
'cms': 'kt',
'v-cms' : 'hftmin',
'decideg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
default:{}//show base units
};
// Small closure to try and get the multiplier //this returns the factor in which to multiply to convert a unit
// needed from the conversion table
const getUnitMultiplier = () => { const getUnitMultiplier = () => {
if(conversionTable[uiUnitValue] && conversionTable[uiUnitValue][inputUnit]) { if (conversionTable[uiUnitValue]){
return conversionTable[uiUnitValue][inputUnit]; const fromUnits = conversionTable[uiUnitValue];
if (fromUnits[inputUnit]){
const multiplier = unitRatioTable[inputUnit][fromUnits[inputUnit]];
return {'multiplier':multiplier, 'unitName':fromUnits[inputUnit]};
} }
}
return conversionTable['default'][inputUnit]; return {multiplier:1, unitName:inputUnit};
} }
// Get the default multi obj or the custom // Get the default multi obj or the custom
const multiObj = getUnitMultiplier(); const multiObj = getUnitMultiplier();
if(!multiObj) {
return;
}
const multiplier = multiObj.multiplier; const multiplier = multiObj.multiplier;
const unitName = multiObj.unitName; const unitName = multiObj.unitName;
// Update the step, min, and max; as we have the multiplier here. // Update the step, min, and max; as we have the multiplier here.
if (element.attr('type') == 'number') { if (element.attr('type') == 'number') {
element.attr('step', ((multiplier != 1) ? '0.01' : '1')); element.attr('step', ((multiplier != 1) ? '0.01' : '1'));
if (multiplier != 'FAHREN') {
element.attr('min', (element.attr('min') / multiplier).toFixed(2)); element.attr('min', (element.attr('min') / multiplier).toFixed(2));
element.attr('max', (element.attr('max') / multiplier).toFixed(2)); element.attr('max', (element.attr('max') / multiplier).toFixed(2));
} }
}
// Update the input with a new formatted unit // Update the input with a new formatted unit
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)); const convertedValue = Number((oldValue / multiplier).toFixed(2));
const newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue; newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
}
element.val(newValue); element.val(newValue);
element.data('setting-multiplier', multiplier); element.data('setting-multiplier', multiplier);
// Now wrap the input in a display that shows the unit // 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) { self.saveInput = function(input) {
@ -216,8 +350,13 @@ var Settings = (function () {
} else if(setting.type == 'string') { } else if(setting.type == 'string') {
value = input.val(); value = input.val();
} else { } else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1); var multiplier = input.data('setting-multiplier') || 1;
value = parseFloat(input.val()) * multiplier; 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); return mspHelper.setSetting(settingName, value);
}; };

View file

@ -2221,11 +2221,19 @@ ol li {
position: relative; 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 */ /* Position the unit to the right of the wrapper */
.unit_wrapper::after { .unit_wrapper::after {
position: absolute; position: absolute;
top: 2px; top: 2px;
right: .7em; right: .5em;
transition: all .05s ease-in-out; transition: all .05s ease-in-out;
} }
@ -2233,13 +2241,13 @@ ol li {
for arrow buttons will appear to the right of number inputs */ for arrow buttons will appear to the right of number inputs */
.unit_wrapper:hover::after, .unit_wrapper:hover::after,
.unit_wrapper:focus-within::after { .unit_wrapper:focus-within::after {
right: 1.3em; right: 1.0em;
} }
/* Handle Firefox (arrows always shown) */ /* Handle Firefox (arrows always shown) */
@supports (-moz-appearance:none) { @supports (-moz-appearance:none) {
.unit_wrapper::after { .unit_wrapper::after {
right: 1.3em; right: 1.0em;
} }
} }

View file

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

View file

@ -6665,47 +6665,47 @@ MAX7456
01010101 01010101
01010101 01010101
01010101 01010101
01010101 00000000
01010101
01010101
01010101
01010101
01000101
01010101
01000101
00100001
01010101
00100001
00101000
01010100
10100001
01001010
00010010
10000101
01001010
10001010
10000101
01010010
10101010
00010101
01010010
10101010
00010101 00010101
01010100 01010100
10101000 10101010
01010101 10000101
01010100 01010100
10101000 10000000
01010101 10000101
01010101 01010100
00100001 10000000
01010101 10000101
01010101 01010100
00100001 10000000
01010101 10000101
01010101 01010100
01000101 10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10000000
10000101
01010100
10101010
10000101
01010100
10101010
10000101
01010101 01010101
00000000
00010101
01010101 01010101
01010101 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

@ -28,12 +28,12 @@
text-align: left; text-align: left;
border: 1px solid silver; border: 1px solid silver;
border-radius: 3px; border-radius: 3px;
margin-right: 11px;
font-size: 12px; font-size: 12px;
font-weight: normal; font-weight: normal;
} }
.config-section .number input, .config-section .number input,
.config-section .checkbox input,
.tab-configuration .number input { .tab-configuration .number input {
width: 106px; width: 106px;
} }
@ -221,7 +221,7 @@ hr {
.config-section label { .config-section label {
position: absolute; position: absolute;
left: 118px; left: 108px;
} }
.config-section .radio label { .config-section .radio label {

View file

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

View file

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

View file

@ -74,6 +74,12 @@
border-color: rgb(52, 155, 255); 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-c .overlay-color,
.tab-led-strip .gPoint.function-r .overlay-color { .tab-led-strip .gPoint.function-r .overlay-color {
float: left; float: left;
@ -210,6 +216,7 @@
.tab-led-strip .select .function-g { background: green;} .tab-led-strip .select .function-g { background: green;}
/* .tab-led-strip .select .function-b { background: white; color:black;} */ /* .tab-led-strip .select .function-b { background: white; color:black;} */
.tab-led-strip .select .function-r { background: #acacac;} .tab-led-strip .select .function-r { background: #acacac;}
.tab-led-strip .select .function-h { background: skyblue;}
.tab-led-strip .select .functionSelect option { .tab-led-strip .select .functionSelect option {
background: white; background: white;

View file

@ -477,21 +477,19 @@ button {
} }
.tab-osd .settings input { .tab-osd .settings input {
width: 55px; width: 75px;
padding-left: 3px; padding-left: 3px;
height: 18px; height: 18px;
line-height: 20px; line-height: 20px;
text-align: left; text-align: left;
border: 1px solid silver; border: 1px solid silver;
border-radius: 3px; border-radius: 3px;
margin-right: 11px;
font-size: 11px; font-size: 11px;
font-weight: normal; font-weight: normal;
} }
.tab-osd .settings select { .tab-osd .settings select {
width: 75px; width: 75px;
margin-right: 11px;
} }
.tab-osd .settings .switchery { .tab-osd .settings .switchery {

View file

@ -302,7 +302,6 @@
text-align: left; text-align: left;
border: 1px solid silver; border: 1px solid silver;
border-radius: 3px; border-radius: 3px;
margin-right: 11px;
font-weight: normal; font-weight: normal;
} }

View file

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

View file

@ -11,12 +11,12 @@
</div> </div>
<div class="spacer_box settings"> <div class="spacer_box settings">
<div class="number"> <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> <label for="launchIdleThr"><span data-i18n="configurationLaunchIdleThr"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div>
</div> </div>
<div class="number"> <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> <label for="launchMaxAngle"><span data-i18n="configurationLaunchMaxAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div>
</div> </div>
@ -26,7 +26,7 @@
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchVelocityHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchVelocityHelp"></div>
</div> </div>
<div class="number"> <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> <label for="launchAccel"><span data-i18n="configurationLaunchAccel"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchAccelHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchAccelHelp"></div>
</div> </div>
@ -51,12 +51,12 @@
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div>
</div> </div>
<div class="number"> <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> <label for="launchThr"><span data-i18n="configurationLaunchThr"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div>
</div> </div>
<div class="number"> <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> <label for="launchClimbAngle"><span data-i18n="configurationLaunchClimbAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchClimbAngleHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationLaunchClimbAngleHelp"></div>
</div> </div>
@ -84,12 +84,12 @@
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="number"> <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> <label for="idlePower"><span data-i18n="idlePower"></span></label>
<div class="helpicon cf_tip" data-i18n_title="idlePowerHelp"></div> <div class="helpicon cf_tip" data-i18n_title="idlePowerHelp"></div>
</div> </div>
<div class="number"> <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> <label for="cruisePower"><span data-i18n="cruisePower"></span></label>
<div class="helpicon cf_tip" data-i18n_title="cruisePowerHelp"></div> <div class="helpicon cf_tip" data-i18n_title="cruisePowerHelp"></div>
</div> </div>
@ -99,7 +99,7 @@
<div class="helpicon cf_tip" data-i18n_title="cruiseSpeedHelp"></div> <div class="helpicon cf_tip" data-i18n_title="cruiseSpeedHelp"></div>
</div> </div>
<div class="number"> <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> <label for="rthEnergyMargin"><span data-i18n="rthEnergyMargin"></span></label>
<div class="helpicon cf_tip" data-i18n_title="rthEnergyMarginHelp"></div> <div class="helpicon cf_tip" data-i18n_title="rthEnergyMarginHelp"></div>
</div> </div>
@ -116,7 +116,7 @@
<div class="spacer_box"> <div class="spacer_box">
<div class="number"> <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> <label for="cruiseThrottle"><span data-i18n="cruiseThrottle"></span></label>
</div> </div>
@ -133,12 +133,12 @@
</div> </div>
<div class="number"> <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> <label for="minThrottle"><span data-i18n="minThrottle"></span></label>
</div> </div>
<div class="number"> <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> <label for="maxThrottle"><span data-i18n="maxThrottle"></span></label>
</div> </div>
@ -149,7 +149,7 @@
</div> </div>
<div class="number"> <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> <label for="pitchToThrottleThreshold"><span data-i18n="pitchToThrottleThreshold"></span></label>
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleThresholdHelp"></div> <div class="helpicon cf_tip" data-i18n_title="pitchToThrottleThresholdHelp"></div>
</div> </div>
@ -161,19 +161,19 @@
</div> </div>
<div class="number"> <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> <label for="maxBankAngle"><span data-i18n="maxBankAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="maxBankAngleHelp"></div> <div class="helpicon cf_tip" data-i18n_title="maxBankAngleHelp"></div>
</div> </div>
<div class="number"> <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> <label for="maxClimbAngle"><span data-i18n="maxClimbAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="maxClimbAngleHelp"></div> <div class="helpicon cf_tip" data-i18n_title="maxClimbAngleHelp"></div>
</div> </div>
<div class="number"> <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> <label for="maxDiveAngle"><span data-i18n="maxDiveAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="maxDiveAngleHelp"></div> <div class="helpicon cf_tip" data-i18n_title="maxDiveAngleHelp"></div>
</div> </div>
@ -230,7 +230,7 @@
<div class="helpicon cf_tip" data-i18n_title="posholdMaxManualSpeedHelp"></div> <div class="helpicon cf_tip" data-i18n_title="posholdMaxManualSpeedHelp"></div>
</div> </div>
<div class="number"> <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> <label for="max-bank-angle"><span data-i18n="posholdMaxBankAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="posholdMaxBankAngleHelp"></div> <div class="helpicon cf_tip" data-i18n_title="posholdMaxBankAngleHelp"></div>
</div> </div>
@ -239,7 +239,7 @@
<label for="use-mid-throttle"><span data-i18n="posholdHoverMidThrottle"></span></label> <label for="use-mid-throttle"><span data-i18n="posholdHoverMidThrottle"></span></label>
</div> </div>
<div class="number"> <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> <label for="hover-throttle"><span data-i18n="posholdHoverThrottle"></span></label>
</div> </div>
<div class="checkbox"> <div class="checkbox">
@ -301,7 +301,7 @@
</div> </div>
<div class="number"> <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> <label for="brakingBankAngle"><span data-i18n="brakingBankAngle"></span></label>
<div class="helpicon cf_tip" data-i18n_title="brakingBankAngleTip"></div> <div class="helpicon cf_tip" data-i18n_title="brakingBankAngleTip"></div>
</div> </div>
@ -393,13 +393,13 @@
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="number"> <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> <label for="navManualClimbRate"><span data-i18n="navManualClimbRate"></span></label>
<div class="helpicon cf_tip" data-i18n_title="navManualClimbRateHelp"></div> <div class="helpicon cf_tip" data-i18n_title="navManualClimbRateHelp"></div>
</div> </div>
<div class="number"> <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> <label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
<div class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div> <div class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
</div> </div>
@ -427,32 +427,32 @@
</div> </div>
</div> </div>
<div class="config-setion gui_box grey"> <div class="config-section gui_box grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="autoLandingSettings"></div> <div class="spacer_box_title" data-i18n="autoLandingSettings"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="number"> <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> <label for="landMaxAltVspd"><span data-i18n="landMaxAltVspd"></span></label>
<div class="helpicon cf_tip" data-i18n_title="landMaxAltVspdHelp"></div> <div class="helpicon cf_tip" data-i18n_title="landMaxAltVspdHelp"></div>
</div> </div>
<div class="number"> <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> <label for="landSlowdownMaxAlt"><span data-i18n="landSlowdownMaxAlt"></span></label>
<div class="helpicon cf_tip" data-i18n_title="landSlowdownMaxAltHelp"></div> <div class="helpicon cf_tip" data-i18n_title="landSlowdownMaxAltHelp"></div>
</div> </div>
<div class="number"> <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="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> <label for="landMinAltVspd"><span data-i18n="landMinAltVspd"></span></label>
<div class="helpicon cf_tip" data-i18n_title="landMinAltVspdHelp"></div> <div class="helpicon cf_tip" data-i18n_title="landMinAltVspdHelp"></div>
</div> </div>
<div class="number"> <div class="number">
<input id="landSlowdownMinAlt" type="number" data-setting="nav_land_slowdown_minalt" data-setting-multiplier="1" step="1" min="50" max="1000" /> <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> <label for="landSlowdownMinAlt"><span data-i18n="landSlowdownMinAlt"></span></label>
</div> </div>

View file

@ -18,16 +18,8 @@ TABS.auxiliary.initialize = function (callback) {
} }
function get_rc_data() { 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); 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);
}
function load_html() { function load_html() {
sort_modes_for_display(); sort_modes_for_display();

View file

@ -76,64 +76,6 @@
</div> </div>
</div> </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="config-section gui_box grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">

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'; 'use strict';
TABS.configuration = {}; TABS.configuration = {};
@ -30,7 +30,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var loadChainer = new MSPChainerClass(); var loadChainer = new MSPChainerClass();
var loadChain = [ var loadChain = [
mspHelper.loadBfConfig, mspHelper.loadFeatures,
mspHelper.loadArmingConfig, mspHelper.loadArmingConfig,
mspHelper.loadLoopTime, mspHelper.loadLoopTime,
mspHelper.load3dConfig, mspHelper.load3dConfig,
@ -39,6 +39,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
mspHelper.loadINAVPidConfig, mspHelper.loadINAVPidConfig,
mspHelper.loadVTXConfig, mspHelper.loadVTXConfig,
mspHelper.loadMixerConfig, mspHelper.loadMixerConfig,
mspHelper.loadBoardAlignment,
mspHelper.loadCurrentMeterConfig,
loadCraftName, loadCraftName,
mspHelper.loadMiscV2 mspHelper.loadMiscV2
]; ];
@ -50,7 +52,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var saveChainer = new MSPChainerClass(); var saveChainer = new MSPChainerClass();
var saveChain = [ var saveChain = [
mspHelper.saveBfConfig,
mspHelper.save3dConfig, mspHelper.save3dConfig,
mspHelper.saveSensorAlignment, mspHelper.saveSensorAlignment,
mspHelper.saveAccTrim, mspHelper.saveAccTrim,
@ -59,6 +60,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
mspHelper.saveAdvancedConfig, mspHelper.saveAdvancedConfig,
mspHelper.saveINAVPidConfig, mspHelper.saveINAVPidConfig,
mspHelper.saveVTXConfig, mspHelper.saveVTXConfig,
mspHelper.saveBoardAlignment,
mspHelper.saveCurrentMeterConfig,
saveCraftName, saveCraftName,
mspHelper.saveMiscV2, mspHelper.saveMiscV2,
saveSettings, saveSettings,
@ -133,7 +136,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 // translate to user-selected language
localize(); localize();
@ -146,32 +149,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag); 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 // VTX
var config_vtx = $('.config-vtx'); var config_vtx = $('.config-vtx');
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) { if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
@ -255,7 +232,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0); $('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
// fill board alignment // 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 // fill magnetometer
$('#mag_declination').val(MISC.mag_declination); $('#mag_declination').val(MISC.mag_declination);
@ -270,8 +247,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#voltagescale').val(MISC.vbatscale); $('#voltagescale').val(MISC.vbatscale);
// fill current // fill current
$('#currentscale').val(BF_CONFIG.currentscale); $('#currentscale').val(CURRENT_METER_CONFIG.scale);
$('#currentoffset').val(BF_CONFIG.currentoffset / 10); $('#currentoffset').val(CURRENT_METER_CONFIG.offset / 10);
// fill battery capacity // fill battery capacity
$('#battery_capacity').val(MISC.battery_capacity); $('#battery_capacity').val(MISC.battery_capacity);
@ -351,13 +328,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
craftName = $('input[name="craft_name"]').val(); 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', 'Looptime', FC_CONFIG.loopTime);
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text()); googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());
@ -373,13 +343,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
} }
helper.features.reset(); helper.features.reset();
helper.features.fromUI($('.tab-configuration')); helper.features.fromUI($('.tab-configuration'));
helper.features.execute(function () { helper.features.execute(function () {
BF_CONFIG.board_align_yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10); BOARD_ALIGNMENT.yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
BF_CONFIG.currentscale = parseInt($('#currentscale').val()); CURRENT_METER_CONFIG.scale = parseInt($('#currentscale').val());
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10); CURRENT_METER_CONFIG.offset = Math.round(parseFloat($('#currentoffset').val()) * 10);
saveChainer.execute(); saveChainer.execute();
}); });
}); });

View file

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

View file

@ -9,49 +9,23 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
googleAnalytics.sendAppView('Failsafe'); googleAnalytics.sendAppView('Failsafe');
} }
// Can get rid of this when MSPHelper supports strings (fixed in #7734, awaiting merge)
function load_failssafe_config() { function load_failssafe_config() {
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_config); MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_html);
}
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);
} }
function load_html() { function load_html() {
GUI.load("./tabs/failsafe.html", process_html); GUI.load("./tabs/failsafe.html", Settings.processHtml(function() {
} GUI.simpleBind();
load_failssafe_config();
function process_html() {
// translate to user-selected language // translate to user-selected language
localize(); 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 // 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 // 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) // code below is a temporary fix, which we will be able to remove in the future (hopefully)
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0); $('#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 // set stage 2 failsafe procedure
$('input[type="radio"].procedure').change(function () { $('input[type="radio"].procedure').change(function () {
var element = $(this), var element = $(this),
@ -74,6 +48,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
}); });
// switch (MSPHelper.getSetting('failsafe_procedure')) { // Use once #7734 is merged
switch (FAILSAFE_CONFIG.failsafe_procedure) { switch (FAILSAFE_CONFIG.failsafe_procedure) {
default: default:
case 0: case 0:
@ -99,45 +74,31 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
// Adjust Minimum Distance values when checkbox is checked/unchecked // Adjust Minimum Distance values when checkbox is checked/unchecked
$failsafeUseMinimumDistanceCheckbox.change(function() { $('#failsafe_use_minimum_distance').change(function() {
if ($(this).is(':checked')) { if ($(this).is(':checked')) {
// 20 meters seems like a reasonable default for a minimum distance // No default distance added due to conversions
$failsafeMinDistance.val(2000); $('#failsafe_min_distance_elements').show();
$failsafeMinDistanceElements.show(); $('#failsafe_min_distance_procedure_elements').show();
$failsafeMinDistanceProcedureElements.show();
} else { } else {
// If they uncheck it, clear the distance to 0, which disables this feature // If they uncheck it, clear the distance to 0, which disables this feature
$failsafeMinDistance.val(0); $('#failsafe_min_distance').val(0);
$failsafeMinDistanceElements.hide(); $('#failsafe_min_distance_elements').hide();
$failsafeMinDistanceProcedureElements.hide(); $('#failsafe_min_distance_procedure_elements').hide();
} }
}); });
// Set initial state of controls according to data // Set initial state of controls according to data
if (FAILSAFE_CONFIG.failsafe_min_distance > 0) { if ( $('#failsafe_min_distance').val() > 0) {
$failsafeUseMinimumDistanceCheckbox.prop('checked', true); $('#failsafe_use_minimum_distance').prop('checked', true);
$failsafeMinDistanceElements.show(); $('#failsafe_min_distance_elements').show();
$failsafeMinDistanceProcedureElements.show(); $('#failsafe_min_distance_procedure_elements').show();
} else { } else {
$failsafeUseMinimumDistanceCheckbox.prop('checked', false); $('#failsafe_use_minimum_distance').prop('checked', false);
$failsafeMinDistanceElements.hide(); $('#failsafe_min_distance_elements').hide();
$failsafeMinDistanceProcedureElements.hide(); $('#failsafe_min_distance_procedure_elements').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 () { $('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')) { if ($('input[id="land"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 0; FAILSAFE_CONFIG.failsafe_procedure = 0;
} else if ($('input[id="drop"]').is(':checked')) { } else if ($('input[id="drop"]').is(':checked')) {
@ -148,36 +109,39 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
FAILSAFE_CONFIG.failsafe_procedure = 3; 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, savePhaseTwo);
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_bf_config); });
GUI.content_ready(callback);
}));
} }
function save_bf_config() { load_failssafe_config();
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
}
function save_to_eeprom() { function savePhaseTwo() {
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot); Settings.saveInputs().then(function () {
var self = this;
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
setTimeout(function () {
$(self).html(oldText);
}, 2000);
reboot();
});
} }
function reboot() { function reboot() {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function () { GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize); MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
}); });
} }
function reinitialize() { function reinitialize() {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceRebooting')); GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect($('.tab_failsafe a')); GUI.handleReconnect($('.tab_failsafe a'));
} }
save_failssafe_config();
});
GUI.content_ready(callback);
}
}; };
TABS.failsafe.cleanup = function (callback) { TABS.failsafe.cleanup = function (callback) {

View file

@ -1,8 +1,78 @@
<div class="tab-gps"> <div class="tab-gps toolbar_fixed_bottom">
<div class="content_wrapper"> <div class="content_wrapper">
<div class="tab_title" data-i18n="tabGPS">GPS</div> <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="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 grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="gpsHead"></div> <div class="spacer_box_title" data-i18n="gpsHead"></div>
@ -80,7 +150,7 @@
</div> </div>
</div> </div>
<div class="cf_column threefourth_left"> <div class="cf_column twothird">
<div class="gui_box grey gps_map"> <div class="gui_box grey gps_map">
<div class="gui_box_titlebar" style="margin-bottom: 0;"> <div class="gui_box_titlebar" style="margin-bottom: 0;">
<div class="spacer_box_title" data-i18n="gpsMapHead"></div> <div class="spacer_box_title" data-i18n="gpsMapHead"></div>
@ -94,4 +164,9 @@
</div> </div>
</div> </div>
<div class="content_toolbar">
<div class="btn save_btn">
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
</div>
</div>
</div> </div>

View file

@ -1,3 +1,4 @@
/*global $,MSPChainerClass,googleAnalytics,mspHelper,MSPCodes,GUI,chrome,MSP,TABS,Settings,helper,ol*/
'use strict'; 'use strict';
TABS.gps = {}; TABS.gps = {};
@ -8,11 +9,48 @@ TABS.gps.initialize = function (callback) {
googleAnalytics.sendAppView('GPS'); googleAnalytics.sendAppView('GPS');
} }
function load_html() { var loadChainer = new MSPChainerClass();
GUI.load("./tabs/gps.html", process_html);
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 cursorInitialized = false;
let iconStyle; let iconStyle;
@ -23,6 +61,36 @@ TABS.gps.initialize = function (callback) {
function process_html() { function process_html() {
localize(); 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({ let mapView = new ol.View({
center: ol.proj.fromLonLat([0, 0]), center: ol.proj.fromLonLat([0, 0]),
zoom: 15 zoom: 15
@ -172,6 +240,29 @@ TABS.gps.initialize = function (callback) {
get_raw_gps_data(); 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); GUI.content_ready(callback);
} }

View file

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

View file

@ -17,7 +17,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
TABS.led_strip.overlays = ['t', 's', 'i', 'w']; TABS.led_strip.overlays = ['t', 's', 'i', 'w'];
} else { } else {
TABS.led_strip.functions = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l', 'o', 'n']; 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.baseFuncs = ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'];
TABS.led_strip.overlays = ['t', 'o', 'b', 'n', 'i', 'w']; TABS.led_strip.overlays = ['t', 'o', 'b', 'n', 'i', 'w'];
} }
@ -799,6 +799,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.modifiers').hide(); $('.modifiers').hide();
$('.blinkers').hide(); $('.blinkers').hide();
$('.warningOverlay').hide(); $('.warningOverlay').hide();
$('.channel_info').hide();
if (areOverlaysActive(activeFunction)) if (areOverlaysActive(activeFunction))
$('.overlays').show(); $('.overlays').show();
@ -867,6 +868,10 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.mode_color-6-0').show(); // disarmed $('.mode_color-6-0').show(); // disarmed
$('.mode_color-6-1').show(); // armed $('.mode_color-6-1').show(); // armed
break; break;
case "function-h": // Channel
$('.special_colors').hide();
$('.channel_info').show();
break;
case "function-r": // Ring case "function-r": // Ring
default: default:

View file

@ -438,7 +438,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
$("[data-role='role-servo-add']").click(function () { $("[data-role='role-servo-add']").click(function () {
if (SERVO_RULES.hasFreeSlots()) { 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(); renderServoMixRules();
renderOutputMapping(); renderOutputMapping();
} }

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'; 'use strict';
var var
@ -17,7 +17,7 @@ TABS.onboard_logging.initialize = function (callback) {
} }
if (CONFIGURATOR.connectionValid) { 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_DATAFLASH_SUMMARY, false, false, function() {
MSP.send_message(MSPCodes.MSP_SDCARD_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); MSP.send_message(MSPCodes.MSP2_BLACKBOX_CONFIG, false, false, load_html);
@ -59,7 +59,7 @@ TABS.onboard_logging.initialize = function (callback) {
dataflashPresent = DATAFLASH.totalSize > 0, dataflashPresent = DATAFLASH.totalSize > 0,
blackboxSupport = false; blackboxSupport = false;
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(BF_CONFIG.features, 19)) { if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(FEATURES, 19)) {
blackboxSupport = true; blackboxSupport = true;
} }

View file

@ -123,17 +123,17 @@
<span data-i18n="osd_time_alarm"></span> <span data-i18n="osd_time_alarm"></span>
</label> </label>
<label for="osd_alt_alarm"> <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> <span data-i18n="osd_alt_alarm"></span>
</label> </label>
<div class="helpicon cf_tip" data-i18n_title="osdAlarmMAX_NEG_ALTITUDE_HELP"></div> <div class="helpicon cf_tip" data-i18n_title="osdAlarmMAX_NEG_ALTITUDE_HELP"></div>
<label for="osd_neg_alt_alarm"> <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> <span data-i18n="osd_neg_alt_alarm"></span>
</label> </label>
<div class="helpicon cf_tip" data-i18n_title="osdAlarmDIST_HELP"></div> <div class="helpicon cf_tip" data-i18n_title="osdAlarmDIST_HELP"></div>
<label for="osd_dist_alarm"> <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> <span data-i18n="osd_dist_alarm"></span>
</label> </label>
<div class="helpicon cf_tip" data-i18n_title="osdAlarmGFORCE_HELP"></div> <div class="helpicon cf_tip" data-i18n_title="osdAlarmGFORCE_HELP"></div>
@ -157,27 +157,27 @@
<span data-i18n="osd_current_alarm"></span> <span data-i18n="osd_current_alarm"></span>
</label> </label>
<label for="imu_temp_alarm_min"> <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> <span data-i18n="osd_imu_temp_alarm_min"></span>
</label> </label>
<label for="imu_temp_alarm_max"> <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> <span data-i18n="osd_imu_temp_alarm_max"></span>
</label> </label>
<label for="baro_temp_alarm_min"> <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> <span data-i18n="osd_baro_temp_alarm_min"></span>
</label> </label>
<label for="baro_temp_alarm_max"> <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> <span data-i18n="osd_baro_temp_alarm_max"></span>
</label> </label>
<label for="esc_temp_alarm_min"> <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> <span data-i18n="osd_esc_temp_alarm_min"></span>
</label> </label>
<label for="esc_temp_alarm_max"> <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> <span data-i18n="osd_esc_temp_alarm_max"></span>
</label> </label>
<div class="helpicon cf_tip" data-i18n_title="osdalarmLQ_HELP"></div> <div class="helpicon cf_tip" data-i18n_title="osdalarmLQ_HELP"></div>

View file

@ -2041,13 +2041,18 @@ OSD.updateDisplaySize = function () {
video_type = 'PAL'; video_type = 'PAL';
} }
// save the original OSD element positions. // 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 = []; var origPos = [];
for (var ii = 0; ii < OSD.data.items.length; ii++) { for (var jj = 0; jj < OSD.data.items.length; jj++) {
origPos.push(OSD.msp.helpers.pack.position(OSD.data.items[ii])); 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]; FONT.constants.SIZES.LINE = OSD.constants.VIDEO_COLS[video_type];
OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type; OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type;
@ -2058,16 +2063,20 @@ OSD.updateDisplaySize = function () {
total: OSD.constants.VIDEO_BUFFER_CHARS[video_type] total: OSD.constants.VIDEO_BUFFER_CHARS[video_type]
}; };
// recalculate the OSD element positions for the new cols per line // re-calculate the OSD element positions for each layout
for (var ii = 0; ii < OSD.data.items.length; ii++) { for (var ii = 0; ii < OSD.data.layout_count; ii++) {
var item = OSD.msp.helpers.unpack.position(origPos[ii]); var origPos = osdLayouts[ii];
// do not recalculate anything not visible or outside of the screen var items = OSD.data.layouts[ii];
if (item.isVisible && item.x < OSD.data.display_size.x && item.y < OSD.data.display_size.y) { for (var jj = 0; jj < OSD.data.item_count; jj++) {
OSD.data.items[ii] = item; 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 // set the preview size based on the video type
$('.third_left').toggleClass('preview_hd_side', (video_type == 'HD')) $('.third_left').toggleClass('preview_hd_side', (video_type == 'HD'))
$('.preview').toggleClass('preview_hd cut43_left', (video_type == 'HD')) $('.preview').toggleClass('preview_hd cut43_left', (video_type == 'HD'))
$('.third_right').toggleClass('preview_hd_side', (video_type == 'HD')) $('.third_right').toggleClass('preview_hd_side', (video_type == 'HD'))
@ -2124,7 +2133,7 @@ OSD.msp = {
}, },
pack: { pack: {
position: function (display_item) { 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); | ((display_item.y & 0x3F) << 6) | (display_item.x & 0x3F);
} }
} }

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'; 'use strict';
TABS.outputs = { TABS.outputs = {
@ -24,7 +24,7 @@ TABS.outputs.initialize = function (callback) {
loadChainer.setChain([ loadChainer.setChain([
mspHelper.loadMiscV2, mspHelper.loadMiscV2,
mspHelper.loadBfConfig, mspHelper.loadFeatures,
mspHelper.load3dConfig, mspHelper.load3dConfig,
mspHelper.loadMotors, mspHelper.loadMotors,
mspHelper.loadMotorMixRules, mspHelper.loadMotorMixRules,
@ -46,7 +46,6 @@ TABS.outputs.initialize = function (callback) {
saveSettings, saveSettings,
mspHelper.sendServoConfigurations, mspHelper.sendServoConfigurations,
mspHelper.saveAdvancedConfig, mspHelper.saveAdvancedConfig,
mspHelper.saveBfConfig,
mspHelper.saveMiscV2, mspHelper.saveMiscV2,
mspHelper.saveToEeprom mspHelper.saveToEeprom
]); ]);
@ -65,7 +64,7 @@ TABS.outputs.initialize = function (callback) {
function onLoad() { function onLoad() {
self.feature3DEnabled = bit_check(BF_CONFIG.features, 12); self.feature3DEnabled = bit_check(FEATURES, 12);
process_motors(); process_motors();
process_servos(); process_servos();
@ -193,7 +192,7 @@ TABS.outputs.initialize = function (callback) {
$('#servo-rate-container').show(); $('#servo-rate-container').show();
helper.features.updateUI($('.tab-motors'), BF_CONFIG.features); helper.features.updateUI($('.tab-motors'), FEATURES);
GUI.simpleBind(); GUI.simpleBind();
let $reversibleMotorCheckbox = $('#feature-12'); let $reversibleMotorCheckbox = $('#feature-12');

View file

@ -15,7 +15,7 @@ TABS.pid_tuning.initialize = function (callback) {
mspHelper.loadINAVPidConfig, mspHelper.loadINAVPidConfig,
mspHelper.loadPidAdvanced, mspHelper.loadPidAdvanced,
mspHelper.loadFilterConfig, mspHelper.loadFilterConfig,
mspHelper.loadBfConfig mspHelper.loadFeatures
]; ];
loadChain.push(mspHelper.loadRateProfileData); loadChain.push(mspHelper.loadRateProfileData);
@ -101,7 +101,7 @@ TABS.pid_tuning.initialize = function (callback) {
if (have_sensor(sensors_detected, 'mag')) { if (have_sensor(sensors_detected, 'mag')) {
$('#pid_mag').show(); $('#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(); $('#pid_gps').show();
} }
if (have_sensor(sensors_detected, 'sonar')) { if (have_sensor(sensors_detected, 'sonar')) {
@ -132,7 +132,7 @@ TABS.pid_tuning.initialize = function (callback) {
} }
helper.tabs.init($('.tab-pid_tuning')); 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); hideUnusedPids(CONFIG.activeSensors);

View file

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