mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-14 20:10:11 +03:00
Merge branch 'master' into arntlse_safehome_mp
This commit is contained in:
commit
dbfbd31c41
37 changed files with 2114 additions and 1430 deletions
|
@ -698,8 +698,8 @@
|
||||||
"configurationThrottleMinimumCommand": {
|
"configurationThrottleMinimumCommand": {
|
||||||
"message": "Minimum Command"
|
"message": "Minimum Command"
|
||||||
},
|
},
|
||||||
"configurationBatteryVoltage": {
|
"configurationVoltageCurrentSensor": {
|
||||||
"message": "Battery Voltage"
|
"message": "Voltage and Current Sensors"
|
||||||
},
|
},
|
||||||
"configurationBatteryCurrent": {
|
"configurationBatteryCurrent": {
|
||||||
"message": "Battery Current"
|
"message": "Battery Current"
|
||||||
|
@ -714,13 +714,13 @@
|
||||||
"message": "Number of cells (0 = auto)"
|
"message": "Number of cells (0 = auto)"
|
||||||
},
|
},
|
||||||
"configurationBatteryCellsHelp": {
|
"configurationBatteryCellsHelp": {
|
||||||
"message": "Set this to the number of cells of your battery to disable automatic cell count detection or to make the automatic switching of battery profiles possible"
|
"message": "Set this to the number of cells of your battery to disable automatic cell count detection or to make the automatic switching of battery profiles possible. 7S, 9S and 11S batteries cannot be autodetected."
|
||||||
},
|
},
|
||||||
"configurationBatteryCellDetectVoltage": {
|
"configurationBatteryCellDetectVoltage": {
|
||||||
"message": "Maximum cell voltage for cell count detection"
|
"message": "Maximum cell voltage for cell count detection"
|
||||||
},
|
},
|
||||||
"configurationBatteryCellDetectVoltageHelp": {
|
"configurationBatteryCellDetectVoltageHelp": {
|
||||||
"message": "Maximum cell voltage used for cell count autodetection. Should be higher than maximum cell voltage to take into account possible drift in measured voltage and keep cell count detection accurate"
|
"message": "Maximum cell voltage used for cell count autodetection. Should be higher than maximum cell voltage to take into account possible drift in measured voltage and keep cell count detection accurate."
|
||||||
},
|
},
|
||||||
"configurationBatteryMinimum": {
|
"configurationBatteryMinimum": {
|
||||||
"message": "Minimum Cell Voltage"
|
"message": "Minimum Cell Voltage"
|
||||||
|
@ -734,10 +734,13 @@
|
||||||
"configurationBatteryScale": {
|
"configurationBatteryScale": {
|
||||||
"message": "Voltage Scale"
|
"message": "Voltage Scale"
|
||||||
},
|
},
|
||||||
"configurationCurrent": {
|
"configurationBatteryVoltage": {
|
||||||
"message": "Current Sensor"
|
"message": "Battery Voltage"
|
||||||
},
|
},
|
||||||
"configurationCurrentScale": {
|
"configurationCurrentScale": {
|
||||||
|
"message": "Current Meter Scale"
|
||||||
|
},
|
||||||
|
"configurationCurrentScaleHelp": {
|
||||||
"message": "Scale the output voltage to milliamps [1/10th mV/A]"
|
"message": "Scale the output voltage to milliamps [1/10th mV/A]"
|
||||||
},
|
},
|
||||||
"configurationCurrentOffset": {
|
"configurationCurrentOffset": {
|
||||||
|
@ -746,8 +749,11 @@
|
||||||
"configurationBatteryMultiwiiCurrent": {
|
"configurationBatteryMultiwiiCurrent": {
|
||||||
"message": "Enable support for legacy Multiwii MSP current output"
|
"message": "Enable support for legacy Multiwii MSP current output"
|
||||||
},
|
},
|
||||||
"configurationBatteryCapacity": {
|
"configurationBatterySettings": {
|
||||||
"message": "Battery Capacity"
|
"message": "Battery Settings"
|
||||||
|
},
|
||||||
|
"configurationBatterySettingsHelp": {
|
||||||
|
"message": "These settings apply to the currently selected battery profile "
|
||||||
},
|
},
|
||||||
"configurationBatteryCapacityValue": {
|
"configurationBatteryCapacityValue": {
|
||||||
"message": "Capacity"
|
"message": "Capacity"
|
||||||
|
@ -1037,6 +1043,9 @@
|
||||||
"portsFunction_DJI_FPV": {
|
"portsFunction_DJI_FPV": {
|
||||||
"message": "DJI FPV VTX"
|
"message": "DJI FPV VTX"
|
||||||
},
|
},
|
||||||
|
"portsFunction_IMU2": {
|
||||||
|
"message": "Secondary IMU"
|
||||||
|
},
|
||||||
"pidTuningName": {
|
"pidTuningName": {
|
||||||
"message": "Name"
|
"message": "Name"
|
||||||
},
|
},
|
||||||
|
@ -1053,7 +1062,7 @@
|
||||||
"message": "FeedForward"
|
"message": "FeedForward"
|
||||||
},
|
},
|
||||||
"pidTuningControlDerivative": {
|
"pidTuningControlDerivative": {
|
||||||
"message": "Constrol Derivative"
|
"message": "Control Derivative"
|
||||||
},
|
},
|
||||||
"pidTuningRollPitchRate": {
|
"pidTuningRollPitchRate": {
|
||||||
"message": "ROLL & PITCH rate"
|
"message": "ROLL & PITCH rate"
|
||||||
|
@ -1123,7 +1132,7 @@
|
||||||
},
|
},
|
||||||
|
|
||||||
"receiverHelp": {
|
"receiverHelp": {
|
||||||
"message": "Please read receiver chapter of the documentation. Configure serial port (if required), receiver mode (serial/ppm/pwm), provider (for serial receivers), bind receiver, set channel map, configure channel endpoints/range on TX so that all channels go from ~1000 to ~2000. Set midpoint (default 1500), trim channels to 1500, configure stick deadband, verify behaviour when TX is off or out of range.<br /><span style=\"color: red\">IMPORTANT:</span> Before flying read failsafe chapter of documentation and configure failsafe."
|
"message": "Please read receiver chapter of the documentation. Configure serial port (if required), receiver mode (serial/ppm/pwm), provider (for serial receivers), bind receiver, set channel map, configure channel endpoints/range on TX so that all channels go from ~1000 to ~2000. Set midpoint (default 1500), trim channels to 1500, configure stick deadband, verify behaviour when TX is off or out of range. Make sure that the channel values all increase when you push the sticks up and to the right. If not, reverse the channel in the TX. Do not apply any other mixing in the TX.<br /><span style=\"color: red\">IMPORTANT:</span> Before flying read failsafe chapter of documentation and configure failsafe."
|
||||||
},
|
},
|
||||||
"receiverThrottleMid": {
|
"receiverThrottleMid": {
|
||||||
"message": "Throttle MID"
|
"message": "Throttle MID"
|
||||||
|
@ -1278,138 +1287,150 @@
|
||||||
"message": "Pitch & Roll I Adjustment"
|
"message": "Pitch & Roll I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction8": {
|
"adjustmentsFunction8": {
|
||||||
"message": "Pitch & Roll D/FF Adjustment"
|
"message": "Pitch & Roll D"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction9": {
|
"adjustmentsFunction9": {
|
||||||
"message": "Yaw P Adjustment"
|
"message": "Pitch & Roll CD/FF Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction10": {
|
"adjustmentsFunction10": {
|
||||||
"message": "Yaw I Adjustment"
|
|
||||||
},
|
|
||||||
"adjustmentsFunction11": {
|
|
||||||
"message": "Yaw D/FF Adjustment"
|
|
||||||
},
|
|
||||||
"adjustmentsFunction12": {
|
|
||||||
"message": "Rate Profile Selection"
|
|
||||||
},
|
|
||||||
"adjustmentsFunction13": {
|
|
||||||
"message": "Pitch Rate"
|
|
||||||
},
|
|
||||||
"adjustmentsFunction14": {
|
|
||||||
"message": "Roll Rate"
|
|
||||||
},
|
|
||||||
"adjustmentsFunction15": {
|
|
||||||
"message": "Pitch P Adjustment"
|
"message": "Pitch P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction16": {
|
"adjustmentsFunction11": {
|
||||||
"message": "Pitch I Adjustment"
|
"message": "Pitch I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction17": {
|
"adjustmentsFunction12": {
|
||||||
"message": "Pitch D/FF Adjustment"
|
"message": "Pitch D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction18": {
|
"adjustmentsFunction13": {
|
||||||
|
"message": "Pitch CD/FF Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction14": {
|
||||||
"message": "Roll P Adjustment"
|
"message": "Roll P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction19": {
|
"adjustmentsFunction15": {
|
||||||
"message": "Roll I Adjustment"
|
"message": "Roll I Adjustment"
|
||||||
},
|
},
|
||||||
|
"adjustmentsFunction16": {
|
||||||
|
"message": "Roll D Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction17": {
|
||||||
|
"message": "Roll CD/FF Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction18": {
|
||||||
|
"message": "Yaw P Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction19": {
|
||||||
|
"message": "Yaw I Adjustment"
|
||||||
|
},
|
||||||
"adjustmentsFunction20": {
|
"adjustmentsFunction20": {
|
||||||
"message": "Roll D/FF Adjustment"
|
"message": "Yaw D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction21": {
|
"adjustmentsFunction21": {
|
||||||
"message": "RC Yaw Expo Adjustment"
|
"message": "Yaw CD/FF Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction22": {
|
"adjustmentsFunction22": {
|
||||||
"message": "Manual RC Expo Adjustment"
|
"message": "Rate Profile Selection"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction23": {
|
"adjustmentsFunction23": {
|
||||||
"message": "Manual RC Yaw Expo Adjustment"
|
"message": "Pitch Rate"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction24": {
|
"adjustmentsFunction24": {
|
||||||
"message": "Manual Pitch & Roll Rate Adjustment"
|
"message": "Roll Rate"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction25": {
|
"adjustmentsFunction25": {
|
||||||
"message": "Manual Roll Rate Adjustment"
|
"message": "RC Yaw Expo Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction26": {
|
"adjustmentsFunction26": {
|
||||||
"message": "Manual Pitch Rate Adjustment"
|
"message": "Manual RC Expo Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction27": {
|
"adjustmentsFunction27": {
|
||||||
"message": "Manual Yaw Rate Adjustment"
|
"message": "Manual RC Yaw Expo Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction28": {
|
"adjustmentsFunction28": {
|
||||||
"message": "Navigation FW Cruise Throttle Adjustment"
|
"message": "Manual Pitch & Roll Rate Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction29": {
|
"adjustmentsFunction29": {
|
||||||
"message": "Navigation FW Pitch To Throttle Adjustment"
|
"message": "Manual Roll Rate Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction30": {
|
"adjustmentsFunction30": {
|
||||||
"message": "Board Roll Alignment Adjustment"
|
"message": "Manual Pitch Rate Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction31": {
|
"adjustmentsFunction31": {
|
||||||
"message": "Board Pitch Alignment Adjustment"
|
"message": "Manual Yaw Rate Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction32": {
|
"adjustmentsFunction32": {
|
||||||
"message": "Level P Adjustment"
|
"message": "Navigation FW Cruise Throttle Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction33": {
|
"adjustmentsFunction33": {
|
||||||
"message": "Level I Adjustment"
|
"message": "Navigation FW Pitch To Throttle Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction34": {
|
"adjustmentsFunction34": {
|
||||||
"message": "Level D Adjustment"
|
"message": "Board Roll Alignment Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction35": {
|
"adjustmentsFunction35": {
|
||||||
"message": "Pos XY P Adjustment"
|
"message": "Board Pitch Alignment Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction36": {
|
"adjustmentsFunction36": {
|
||||||
"message": "Pos XY I Adjustment"
|
"message": "Level P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction37": {
|
"adjustmentsFunction37": {
|
||||||
"message": "Pos XY D Adjustment"
|
"message": "Level I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction38": {
|
"adjustmentsFunction38": {
|
||||||
"message": "Pos Z P Adjustment"
|
"message": "Level D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction39": {
|
"adjustmentsFunction39": {
|
||||||
"message": "Pos Z I Adjustment"
|
"message": "Pos XY P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction40": {
|
"adjustmentsFunction40": {
|
||||||
"message": "Pos Z D Adjustment"
|
"message": "Pos XY I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction41": {
|
"adjustmentsFunction41": {
|
||||||
"message": "Heading P Adjustment"
|
"message": "Pos XY D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction42": {
|
"adjustmentsFunction42": {
|
||||||
"message": "Vel XY P Adjustment"
|
"message": "Pos Z P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction43": {
|
"adjustmentsFunction43": {
|
||||||
"message": "Vel XY I Adjustment"
|
"message": "Pos Z I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction44": {
|
"adjustmentsFunction44": {
|
||||||
"message": "Vel XY D Adjustment"
|
"message": "Pos Z D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction45": {
|
"adjustmentsFunction45": {
|
||||||
"message": "Vel Z P Adjustment"
|
"message": "Heading P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction46": {
|
"adjustmentsFunction46": {
|
||||||
"message": "Vel Z I Adjustment"
|
"message": "Vel XY P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction47": {
|
"adjustmentsFunction47": {
|
||||||
"message": "Vel Z D Adjustment"
|
"message": "Vel XY I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction48": {
|
"adjustmentsFunction48": {
|
||||||
"message": "FW min thr down pitch angle Adjustment"
|
"message": "Vel XY D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction49": {
|
"adjustmentsFunction49": {
|
||||||
"message": "VTX power level Adjustment"
|
"message": "Vel Z P Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction50": {
|
"adjustmentsFunction50": {
|
||||||
"message": "Thrust PID Attenuation (TPA) Adjustment"
|
"message": "Vel Z I Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction51": {
|
"adjustmentsFunction51": {
|
||||||
"message": "TPA Breakpoint Adjustment"
|
"message": "Vel Z D Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsFunction52": {
|
"adjustmentsFunction52": {
|
||||||
|
"message": "FW min thr down pitch angle Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction53": {
|
||||||
|
"message": "VTX power level Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction54": {
|
||||||
|
"message": "Thrust PID Attenuation (TPA) Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction55": {
|
||||||
|
"message": "TPA Breakpoint Adjustment"
|
||||||
|
},
|
||||||
|
"adjustmentsFunction56": {
|
||||||
"message": "Control Smoothness Adjustment"
|
"message": "Control Smoothness Adjustment"
|
||||||
},
|
},
|
||||||
"adjustmentsSave": {
|
"adjustmentsSave": {
|
||||||
|
@ -2345,13 +2366,16 @@
|
||||||
"message": "Programming"
|
"message": "Programming"
|
||||||
},
|
},
|
||||||
"tabAdvancedTuning": {
|
"tabAdvancedTuning": {
|
||||||
"message": "Advanced tuning"
|
"message": "Advanced Tuning"
|
||||||
},
|
},
|
||||||
"advancedTuningSave": {
|
"advancedTuningSave": {
|
||||||
"message": "Save and Reboot"
|
"message": "Save and Reboot"
|
||||||
},
|
},
|
||||||
"tabAdvancedTuningTitle": {
|
"tabAdvancedTuningTitle": {
|
||||||
"message": "Advanced tuning"
|
"message": "Advanced Tuning"
|
||||||
|
},
|
||||||
|
"tabAdvancedTuningGenericTitle": {
|
||||||
|
"message": "Generic settings"
|
||||||
},
|
},
|
||||||
"presetApplyHead": {
|
"presetApplyHead": {
|
||||||
"message": "Applies following settings:"
|
"message": "Applies following settings:"
|
||||||
|
@ -2422,6 +2446,12 @@
|
||||||
"posholdHoverMidThrottle": {
|
"posholdHoverMidThrottle": {
|
||||||
"message": "Use mid. throttle for ALTHOLD"
|
"message": "Use mid. throttle for ALTHOLD"
|
||||||
},
|
},
|
||||||
|
"mcWpSlowdown": {
|
||||||
|
"message": "Slow down when approaching waypoint"
|
||||||
|
},
|
||||||
|
"mcWpSlowdownHelp": {
|
||||||
|
"message": "When enabled, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When disabled, NAV engine will continue to the next waypoint and turn as it goes."
|
||||||
|
},
|
||||||
"positionEstimatorConfiguration": {
|
"positionEstimatorConfiguration": {
|
||||||
"message": "Position Estimator"
|
"message": "Position Estimator"
|
||||||
},
|
},
|
||||||
|
@ -2441,7 +2471,7 @@
|
||||||
"message": "Horizontal speed GPS weight"
|
"message": "Horizontal speed GPS weight"
|
||||||
},
|
},
|
||||||
"positionEstimatorConfigurationDisclaimer": {
|
"positionEstimatorConfigurationDisclaimer": {
|
||||||
"message": "This value should be changed very carefully. In most cases there is not need to change that. For advanced users only!"
|
"message": "These values should be changed very carefully. In most cases there is no need to change them. For advanced users only!"
|
||||||
},
|
},
|
||||||
"gps_min_sats": {
|
"gps_min_sats": {
|
||||||
"message": "Min. GPS satellites for a valid fix"
|
"message": "Min. GPS satellites for a valid fix"
|
||||||
|
@ -2449,8 +2479,8 @@
|
||||||
"w_z_baro_p_help": {
|
"w_z_baro_p_help": {
|
||||||
"message": "When this value is set to <strong>0</strong>, barometer is not used for altitude computation"
|
"message": "When this value is set to <strong>0</strong>, barometer is not used for altitude computation"
|
||||||
},
|
},
|
||||||
"w_z_gos_p_help": {
|
"w_z_gps_p_help": {
|
||||||
"message": "When this value is set to <strong>0</strong>, GPS is not used for altitude computation"
|
"message": "This setting is only used when no barometer is installed and <strong>inav_use_gps_no_baro</strong> is configured."
|
||||||
},
|
},
|
||||||
"wirelessModeSwitch": {
|
"wirelessModeSwitch": {
|
||||||
"message": "Wireless mode"
|
"message": "Wireless mode"
|
||||||
|
@ -2467,9 +2497,18 @@
|
||||||
"rthClimbFirst": {
|
"rthClimbFirst": {
|
||||||
"message": "Climb before RTH"
|
"message": "Climb before RTH"
|
||||||
},
|
},
|
||||||
|
"rthClimbFirstHelp": {
|
||||||
|
"message": "If set to ON or ON_FW_SPIRAL, aircraft will climb to nav_rth_altitude first before turning to head home. If set to OFF, aircraft will turn and head home immediately climbing on the way. For a fixed wing, ON will use a linear climb, ON_FW_SPIRAL will use a loiter turning climb with climb rate set by nav_auto_climb_rate and turn rate set by nav_fw_loiter_radius (ON_FW_SPIRAL is a fixed wing setting and behaves the same as ON for a multirotor)."
|
||||||
|
},
|
||||||
"rthClimbIgnoreEmergency": {
|
"rthClimbIgnoreEmergency": {
|
||||||
"message": "Climb regardless of position sensors health"
|
"message": "Climb regardless of position sensors health"
|
||||||
},
|
},
|
||||||
|
"rthAltControlOverride": {
|
||||||
|
"message": "Override RTH altitude and climb setting with roll/pitch stick"
|
||||||
|
},
|
||||||
|
"rthAltControlOverrideHELP": {
|
||||||
|
"message": "When enabled, the climb on RTH can be canceled by holding full pitch down for >1 second so aircraft will fly home at the current altitude. On fixed wing aircraft, the 'Climb before RTH' setting can be overriden by holding full roll left or right for >1 second so that the plane will turn towards home immediately."
|
||||||
|
},
|
||||||
"rthTailFirst": {
|
"rthTailFirst": {
|
||||||
"message": "Tail first"
|
"message": "Tail first"
|
||||||
},
|
},
|
||||||
|
@ -2531,19 +2570,31 @@
|
||||||
"message": "Max. throttle"
|
"message": "Max. throttle"
|
||||||
},
|
},
|
||||||
"maxBankAngle": {
|
"maxBankAngle": {
|
||||||
"message": "Max. bank angle [degrees]"
|
"message": "Max. navigation bank angle [degrees]"
|
||||||
},
|
},
|
||||||
"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. climb angle [degrees]"
|
"message": "Max. navigation climb angle [degrees]"
|
||||||
},
|
},
|
||||||
"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": {
|
||||||
|
"message": "Max. Alt-hold climb rate [cm/s]"
|
||||||
|
},
|
||||||
|
"navManualClimbRateHelp": {
|
||||||
|
"message": "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
|
||||||
|
},
|
||||||
|
"navAutoClimbRate": {
|
||||||
|
"message": "Max. navigation climb rate [cm/s]"
|
||||||
|
},
|
||||||
|
"navAutoClimbRateHelp": {
|
||||||
|
"message": "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
|
||||||
|
},
|
||||||
"maxDiveAngle": {
|
"maxDiveAngle": {
|
||||||
"message": "Max. dive angle [degrees]"
|
"message": "Max. navigation dive angle [degrees]"
|
||||||
},
|
},
|
||||||
"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."
|
||||||
|
@ -2554,6 +2605,18 @@
|
||||||
"pitchToThrottleHelp": {
|
"pitchToThrottleHelp": {
|
||||||
"message": "In navigation modes, each degree of climb will add this many units to the cruise throttle. Conversely, each degree of diving will substract from it."
|
"message": "In navigation modes, each degree of climb will add this many units to the cruise throttle. Conversely, each degree of diving will substract from it."
|
||||||
},
|
},
|
||||||
|
"pitchToThrottleSmoothing": {
|
||||||
|
"message": "Throttle smoothing"
|
||||||
|
},
|
||||||
|
"pitchToThrottleSmoothingHelp": {
|
||||||
|
"message": "How smoothly the autopilot adjusts the throttle level in response to pitch angle changes [0-9]."
|
||||||
|
},
|
||||||
|
"pitchToThrottleThreshold": {
|
||||||
|
"message": "Instantaneous throttle adjustment threshold [centidegrees]"
|
||||||
|
},
|
||||||
|
"pitchToThrottleThresholdHelp": {
|
||||||
|
"message": "The autopilot will instantly adjust the throttle level without smoothing according to pitch to throttle if the pitch angle is more this many centidegrees from the filtered value."
|
||||||
|
},
|
||||||
"loiterRadius": {
|
"loiterRadius": {
|
||||||
"message": "Loiter radius [cm]"
|
"message": "Loiter radius [cm]"
|
||||||
},
|
},
|
||||||
|
@ -2567,7 +2630,37 @@
|
||||||
"message": "Control Smoothness"
|
"message": "Control Smoothness"
|
||||||
},
|
},
|
||||||
"controlSmoothnessHelp": {
|
"controlSmoothnessHelp": {
|
||||||
"message": "How smoothly the autopilot controls the airplane to correct the navigation error [0-9]"
|
"message": "How smoothly the autopilot controls the airplane to correct the navigation error [0-9]."
|
||||||
|
},
|
||||||
|
"powerConfiguration": {
|
||||||
|
"message": "Battery Estimation Settings"
|
||||||
|
},
|
||||||
|
"idlePower": {
|
||||||
|
"message": "Idle power [cW]"
|
||||||
|
},
|
||||||
|
"idlePowerHelp": {
|
||||||
|
"message": "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
|
||||||
|
},
|
||||||
|
"cruisePower": {
|
||||||
|
"message": "Cruise power [cW]"
|
||||||
|
},
|
||||||
|
"cruisePowerHelp": {
|
||||||
|
"message": "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
|
||||||
|
},
|
||||||
|
"cruiseSpeed": {
|
||||||
|
"message": "Cruise speed [cm/s]"
|
||||||
|
},
|
||||||
|
"cruiseSpeedHelp": {
|
||||||
|
"message": "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
|
||||||
|
},
|
||||||
|
"rthEnergyMargin": {
|
||||||
|
"message": "RTH energy margin [%]"
|
||||||
|
},
|
||||||
|
"rthEnergyMarginHelp": {
|
||||||
|
"message": "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation."
|
||||||
|
},
|
||||||
|
"generalNavigationSettings": {
|
||||||
|
"message": "General Navigation Settings"
|
||||||
},
|
},
|
||||||
"waypointConfiguration": {
|
"waypointConfiguration": {
|
||||||
"message": "Waypoint Navigation Settings"
|
"message": "Waypoint Navigation Settings"
|
||||||
|
@ -2579,7 +2672,7 @@
|
||||||
"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 [cm]."
|
||||||
},
|
},
|
||||||
"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."
|
||||||
|
@ -3052,6 +3145,15 @@
|
||||||
"osdSettingMainVoltageDecimals": {
|
"osdSettingMainVoltageDecimals": {
|
||||||
"message": "Main voltage decimals"
|
"message": "Main voltage decimals"
|
||||||
},
|
},
|
||||||
|
"osdElement_OSD_RANGEFINDER": {
|
||||||
|
"message": "Rangefinder distance"
|
||||||
|
},
|
||||||
|
"osdSettingPLUS_CODE_DIGITS_HELP": {
|
||||||
|
"message": "Precision at the equator: 10=13.9x13.9m; 11=2.8x3.5m; 12=56x87cm; 13=11x22cm."
|
||||||
|
},
|
||||||
|
"osdSettingPLUS_CODE_SHORT_HELP": {
|
||||||
|
"message": "Removing 2, 4 and 6 leading digits requires a reference location within, respectively, ~800km, ~40km and ~2km to recover the original coordinates."
|
||||||
|
},
|
||||||
"osdSettingCRSF_LQ_FORMAT_HELP": {
|
"osdSettingCRSF_LQ_FORMAT_HELP": {
|
||||||
"message": "TYPE1 shows LQ% as used by TBS hardware. TYPE2 shows RF Profile Modes (2=150Hz, 1=50Hz, 0=4Hz update rates) and LQ % [0..100%]. Tracer shows RFMode 1 (1=250Hz) and LQ % [0..100%]."
|
"message": "TYPE1 shows LQ% as used by TBS hardware. TYPE2 shows RF Profile Modes (2=150Hz, 1=50Hz, 0=4Hz update rates) and LQ % [0..100%]. Tracer shows RFMode 1 (1=250Hz) and LQ % [0..100%]."
|
||||||
},
|
},
|
||||||
|
@ -3478,6 +3580,18 @@
|
||||||
"dTermMechanics": {
|
"dTermMechanics": {
|
||||||
"message": "D-term mechanics"
|
"message": "D-term mechanics"
|
||||||
},
|
},
|
||||||
|
"tpaMechanics": {
|
||||||
|
"message": "Thrust PID attenuation"
|
||||||
|
},
|
||||||
|
"fw_level_pitch_trim": {
|
||||||
|
"message": "Level Trim [deg]"
|
||||||
|
},
|
||||||
|
"fw_level_pitch_trim_help": {
|
||||||
|
"message": "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
|
||||||
|
},
|
||||||
|
"fwLevelTrimMechanics": {
|
||||||
|
"message": "Fixed Wing Level Trim"
|
||||||
|
},
|
||||||
"d_boost_factor": {
|
"d_boost_factor": {
|
||||||
"message": "D-Boost Factor"
|
"message": "D-Boost Factor"
|
||||||
},
|
},
|
||||||
|
@ -3499,17 +3613,17 @@
|
||||||
"iTermMechanics": {
|
"iTermMechanics": {
|
||||||
"message": "I-term mechanics"
|
"message": "I-term mechanics"
|
||||||
},
|
},
|
||||||
"mc_airmode_type": {
|
"airmode_type": {
|
||||||
"message": "Airmode handling type"
|
"message": "Airmode handling type"
|
||||||
},
|
},
|
||||||
"mc_airmode_type_help": {
|
"airmode_type_help": {
|
||||||
"message": "Defines the Airmode state handling type for Multirotors. <br />Default STICK_CENTER is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). <br />STICK_CENTER_ONCE works like STICK_CENTER, but only until the first time THROTTLE is not low and ROLL/PITCH/YAW sticks are moved. After that, ANTI_WINDUP is deactivated until next arm. Useful for airplanes. <br />THROTTLE_THRESHOLD is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above <i>mc_airmode_threshold</i> and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to THROTTLE_THRESHOLD since it keeps full stabilization no matter what pilot does with the sticks. Airplanes default to STICK_CENTER mode."
|
"message": "Defines the Airmode state handling type. <br />Default STICK_CENTER is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). <br />STICK_CENTER_ONCE works like STICK_CENTER, but only until the first time THROTTLE is not low and ROLL/PITCH/YAW sticks are moved. After that, ANTI_WINDUP is deactivated until next arm. Useful for airplanes. <br />THROTTLE_THRESHOLD is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above <i>airmode_throttle_threshold</i> and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to THROTTLE_THRESHOLD since it keeps full stabilization no matter what pilot does with the sticks. Airplanes default to STICK_CENTER_ONCE mode."
|
||||||
},
|
},
|
||||||
"mc_airmode_threshold": {
|
"airmode_throttle_threshold": {
|
||||||
"message": "Airmode Throttle threshold"
|
"message": "Airmode Throttle threshold"
|
||||||
},
|
},
|
||||||
"mc_airmode_threshold_help": {
|
"airmode_throttle_threshold_help": {
|
||||||
"message": "Defines airmode THROTTLE activation threshold when mc_airmode_type THROTTLE_THRESHOLD is used"
|
"message": "Defines airmode THROTTLE activation threshold when airmode_type THROTTLE_THRESHOLD is used"
|
||||||
},
|
},
|
||||||
"gps_map_center": {
|
"gps_map_center": {
|
||||||
"message": "Center"
|
"message": "Center"
|
||||||
|
@ -3523,6 +3637,12 @@
|
||||||
"antigravityCutoff": {
|
"antigravityCutoff": {
|
||||||
"message": "Antigravity Cutoff Frequency"
|
"message": "Antigravity Cutoff Frequency"
|
||||||
},
|
},
|
||||||
|
"itermBankAngleFreeze": {
|
||||||
|
"message": "Yaw Iterm freeze bank angle"
|
||||||
|
},
|
||||||
|
"itermBankAngleFreezeHelp": {
|
||||||
|
"message": "Freeze yaw Iterm when plane is banked more than this many degrees. This helps to stop the rudder from counteracting turn. 0 disables this feature. Applies only to fixed wing aircraft."
|
||||||
|
},
|
||||||
"ouptputsConfiguration": {
|
"ouptputsConfiguration": {
|
||||||
"message": "Configuration"
|
"message": "Configuration"
|
||||||
},
|
},
|
||||||
|
@ -3645,5 +3765,35 @@
|
||||||
},
|
},
|
||||||
"WaypointOptionP2": {
|
"WaypointOptionP2": {
|
||||||
"message": "P2"
|
"message": "P2"
|
||||||
|
},
|
||||||
|
"rollPitchAdjustmentsMoved": {
|
||||||
|
"message": "Roll & Pitch board orientation is available only in the CLI. Do not use it to trim the airplane for the level flight! Use Fixed Wing Level Trim on the PID tuning tab under Mechanics instead (<strong>fw_level_pitch_trim</strong>)."
|
||||||
|
},
|
||||||
|
"pidId": {
|
||||||
|
"message": "#"
|
||||||
|
},
|
||||||
|
"pidEnabled": {
|
||||||
|
"message": "Enabled"
|
||||||
|
},
|
||||||
|
"pidSetpoint": {
|
||||||
|
"message": "Setpoint"
|
||||||
|
},
|
||||||
|
"pidMeasurement": {
|
||||||
|
"message": "Measurement"
|
||||||
|
},
|
||||||
|
"pidP": {
|
||||||
|
"message": "P-gain"
|
||||||
|
},
|
||||||
|
"pidI": {
|
||||||
|
"message": "I-gain"
|
||||||
|
},
|
||||||
|
"pidD": {
|
||||||
|
"message": "D-gain"
|
||||||
|
},
|
||||||
|
"pidFF": {
|
||||||
|
"message": "FF-gain"
|
||||||
|
},
|
||||||
|
"pidOutput": {
|
||||||
|
"message": "Output"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -106,6 +106,9 @@ sources.js = [
|
||||||
'./js/logicConditionsCollection.js',
|
'./js/logicConditionsCollection.js',
|
||||||
'./js/logicConditionsStatus.js',
|
'./js/logicConditionsStatus.js',
|
||||||
'./js/globalVariablesStatus.js',
|
'./js/globalVariablesStatus.js',
|
||||||
|
'./js/programmingPid.js',
|
||||||
|
'./js/programmingPidCollection.js',
|
||||||
|
'./js/programmingPidStatus.js',
|
||||||
'./js/vtx.js',
|
'./js/vtx.js',
|
||||||
'./main.js',
|
'./main.js',
|
||||||
'./js/tabs.js',
|
'./js/tabs.js',
|
||||||
|
|
|
@ -2,8 +2,8 @@
|
||||||
|
|
||||||
var CONFIGURATOR = {
|
var CONFIGURATOR = {
|
||||||
// all versions are specified and compared using semantic versioning http://semver.org/
|
// all versions are specified and compared using semantic versioning http://semver.org/
|
||||||
'minfirmwareVersionAccepted': '2.6.0',
|
'minfirmwareVersionAccepted': '3.0.0',
|
||||||
'maxFirmwareVersionAccepted': '2.8.0', // Condition is < (lt) so we accept all in 2.2 branch, not 2.3 actualy
|
'maxFirmwareVersionAccepted': '3.1.0', // Condition is < (lt) so we accept all in 3.0 branch
|
||||||
'connectionValid': false,
|
'connectionValid': false,
|
||||||
'connectionValidCliOnly': false,
|
'connectionValidCliOnly': false,
|
||||||
'cliActive': false,
|
'cliActive': false,
|
||||||
|
|
|
@ -61,10 +61,6 @@ helper.defaultsDialog = (function() {
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "dynamic_gyro_notch_enabled",
|
key: "dynamic_gyro_notch_enabled",
|
||||||
value: "ON"
|
value: "ON"
|
||||||
|
@ -89,17 +85,9 @@ helper.defaultsDialog = (function() {
|
||||||
Mechanics
|
Mechanics
|
||||||
*/
|
*/
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.75
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -196,27 +184,55 @@ helper.defaultsDialog = (function() {
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"title": 'Airplane',
|
"title": 'Airplane with a Tail',
|
||||||
"notRecommended": false,
|
"notRecommended": false,
|
||||||
"id": 3,
|
"id": 3,
|
||||||
"reboot": true,
|
"reboot": true,
|
||||||
"settings": [
|
"settings": [
|
||||||
|
{
|
||||||
|
key: "platform_type",
|
||||||
|
value: "AIRPLANE"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "applied_defaults",
|
||||||
|
value: 3
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "gyro_hardware_lpf",
|
key: "gyro_hardware_lpf",
|
||||||
value: "256HZ"
|
value: "256HZ"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "gyro_lpf_hz",
|
key: "gyro_lpf_hz",
|
||||||
|
value: 25
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dterm_lpf_hz",
|
||||||
value: 40
|
value: 40
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "gyro_lpf_type",
|
key: "gyro_lpf_type",
|
||||||
value: "BIQUAD"
|
value: "BIQUAD"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_enabled",
|
||||||
|
value: "ON"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_q",
|
||||||
|
value: 250
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_min_hz",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "motor_pwm_protocol",
|
key: "motor_pwm_protocol",
|
||||||
value: "STANDARD"
|
value: "STANDARD"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "throttle_idle",
|
||||||
|
value: 5.0
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "rc_yaw_expo",
|
key: "rc_yaw_expo",
|
||||||
value: 30
|
value: 30
|
||||||
|
@ -227,15 +243,83 @@ helper.defaultsDialog = (function() {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "roll_rate",
|
key: "roll_rate",
|
||||||
value: 20
|
value: 18
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "pitch_rate",
|
key: "pitch_rate",
|
||||||
value: 15
|
value: 9
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "yaw_rate",
|
key: "yaw_rate",
|
||||||
value: 9
|
value: 3
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_p",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_d",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_xy_p",
|
||||||
|
value: 50
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_turn_assist_pitch_gain",
|
||||||
|
value: 0.5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "max_angle_inclination_rll",
|
||||||
|
value: 350
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_bank_angle",
|
||||||
|
value: 35
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_pitch",
|
||||||
|
value: 15
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_pitch",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_pitch",
|
||||||
|
value: 60
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_roll",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_roll",
|
||||||
|
value: 8
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_roll",
|
||||||
|
value: 40
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_yaw",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_yaw",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_yaw",
|
||||||
|
value: 100
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_acc_ignore_rate",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "airmode_type",
|
||||||
|
value: "STICK_CENTER_ONCE"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "small_angle",
|
key: "small_angle",
|
||||||
|
@ -255,20 +339,12 @@ helper.defaultsDialog = (function() {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "failsafe_mission",
|
key: "failsafe_mission",
|
||||||
value: "OFF"
|
value: "ON"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "nav_wp_radius",
|
key: "nav_wp_radius",
|
||||||
value: 3000
|
value: 1500
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "platform_type",
|
|
||||||
value: "AIRPLANE"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "applied_defaults",
|
|
||||||
value: 3
|
|
||||||
}
|
|
||||||
],
|
],
|
||||||
"features":[
|
"features":[
|
||||||
{
|
{
|
||||||
|
@ -277,6 +353,176 @@ helper.defaultsDialog = (function() {
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
"title": 'Airplane without a Tail (Wing, Delta, etc)',
|
||||||
|
"notRecommended": false,
|
||||||
|
"id": 3,
|
||||||
|
"reboot": true,
|
||||||
|
"settings": [
|
||||||
|
{
|
||||||
|
key: "platform_type",
|
||||||
|
value: "AIRPLANE"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "applied_defaults",
|
||||||
|
value: 3
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "gyro_hardware_lpf",
|
||||||
|
value: "256HZ"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "gyro_lpf_hz",
|
||||||
|
value: 25
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dterm_lpf_hz",
|
||||||
|
value: 40
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "gyro_lpf_type",
|
||||||
|
value: "BIQUAD"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_enabled",
|
||||||
|
value: "ON"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_q",
|
||||||
|
value: 250
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_min_hz",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "motor_pwm_protocol",
|
||||||
|
value: "STANDARD"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "throttle_idle",
|
||||||
|
value: 5.0
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "rc_yaw_expo",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "rc_expo",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "roll_rate",
|
||||||
|
value: 18
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "pitch_rate",
|
||||||
|
value: 9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "yaw_rate",
|
||||||
|
value: 3
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_p",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_d",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_xy_p",
|
||||||
|
value: 50
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_turn_assist_pitch_gain",
|
||||||
|
value: 0.2
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "max_angle_inclination_rll",
|
||||||
|
value: 450
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_bank_angle",
|
||||||
|
value: 45
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_pitch",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_pitch",
|
||||||
|
value: 15
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_pitch",
|
||||||
|
value: 70
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_roll",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_roll",
|
||||||
|
value: 8
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_roll",
|
||||||
|
value: 35
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_yaw",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_yaw",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_yaw",
|
||||||
|
value: 100
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_acc_ignore_rate",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "airmode_type",
|
||||||
|
value: "STICK_CENTER_ONCE"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "small_angle",
|
||||||
|
value: 180
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_control_smoothness",
|
||||||
|
value: 2
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_rth_allow_landing",
|
||||||
|
value: "FS_ONLY"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_rth_altitude",
|
||||||
|
value: 5000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "failsafe_mission",
|
||||||
|
value: "ON"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_wp_radius",
|
||||||
|
value: 1500
|
||||||
|
},
|
||||||
|
],
|
||||||
|
"features":[
|
||||||
|
{
|
||||||
|
bit: 4, // Enable MOTOR_STOP
|
||||||
|
state: true
|
||||||
|
}
|
||||||
|
]
|
||||||
|
},
|
||||||
{
|
{
|
||||||
"title": 'Rovers & Boats',
|
"title": 'Rovers & Boats',
|
||||||
"notRecommended": false,
|
"notRecommended": false,
|
||||||
|
|
72
js/fc.js
72
js/fc.js
|
@ -23,6 +23,8 @@ var CONFIG,
|
||||||
LOGIC_CONDITIONS_STATUS,
|
LOGIC_CONDITIONS_STATUS,
|
||||||
GLOBAL_FUNCTIONS,
|
GLOBAL_FUNCTIONS,
|
||||||
GLOBAL_VARIABLES_STATUS,
|
GLOBAL_VARIABLES_STATUS,
|
||||||
|
PROGRAMMING_PID,
|
||||||
|
PROGRAMMING_PID_STATUS,
|
||||||
SERIAL_CONFIG,
|
SERIAL_CONFIG,
|
||||||
SENSOR_DATA,
|
SENSOR_DATA,
|
||||||
MOTOR_DATA,
|
MOTOR_DATA,
|
||||||
|
@ -66,14 +68,20 @@ var CONFIG,
|
||||||
var FC = {
|
var FC = {
|
||||||
MAX_SERVO_RATE: 125,
|
MAX_SERVO_RATE: 125,
|
||||||
MIN_SERVO_RATE: 0,
|
MIN_SERVO_RATE: 0,
|
||||||
|
isAirplane: function () {
|
||||||
|
return (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE);
|
||||||
|
},
|
||||||
|
isMultirotor: function () {
|
||||||
|
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
|
||||||
|
},
|
||||||
isRpyFfComponentUsed: function () {
|
isRpyFfComponentUsed: function () {
|
||||||
return (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE || MIXER_CONFIG.platformType == PLATFORM_ROVER || MIXER_CONFIG.platformType == PLATFORM_BOAT) || ((MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) && semver.gte(CONFIG.flightControllerVersion, "2.6.0"));
|
return (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE || MIXER_CONFIG.platformType == PLATFORM_ROVER || MIXER_CONFIG.platformType == PLATFORM_BOAT) || ((MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) && semver.gte(CONFIG.flightControllerVersion, "2.6.0"));
|
||||||
},
|
},
|
||||||
isRpyDComponentUsed: function () {
|
isRpyDComponentUsed: function () {
|
||||||
return MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER;
|
return true; // Currently all platforms use D term
|
||||||
},
|
},
|
||||||
isCdComponentUsed: function () {
|
isCdComponentUsed: function () {
|
||||||
return FC.isRpyDComponentUsed();
|
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
|
||||||
},
|
},
|
||||||
resetState: function () {
|
resetState: function () {
|
||||||
SENSOR_STATUS = {
|
SENSOR_STATUS = {
|
||||||
|
@ -173,11 +181,13 @@ var FC = {
|
||||||
ADJUSTMENT_RANGES = [];
|
ADJUSTMENT_RANGES = [];
|
||||||
|
|
||||||
SERVO_CONFIG = [];
|
SERVO_CONFIG = [];
|
||||||
SERVO_RULES = new ServoMixerRuleCollection();
|
SERVO_RULES = new ServoMixerRuleCollection();
|
||||||
MOTOR_RULES = new MotorMixerRuleCollection();
|
MOTOR_RULES = new MotorMixerRuleCollection();
|
||||||
LOGIC_CONDITIONS = new LogicConditionsCollection();
|
LOGIC_CONDITIONS = new LogicConditionsCollection();
|
||||||
LOGIC_CONDITIONS_STATUS = new LogicConditionsStatus();
|
LOGIC_CONDITIONS_STATUS = new LogicConditionsStatus();
|
||||||
GLOBAL_VARIABLES_STATUS = new GlobalVariablesStatus();
|
GLOBAL_VARIABLES_STATUS = new GlobalVariablesStatus();
|
||||||
|
PROGRAMMING_PID = new ProgrammingPidCollection();
|
||||||
|
PROGRAMMING_PID_STATUS = new ProgrammingPidStatus();
|
||||||
|
|
||||||
MIXER_CONFIG = {
|
MIXER_CONFIG = {
|
||||||
yawMotorDirection: 0,
|
yawMotorDirection: 0,
|
||||||
|
@ -575,7 +585,6 @@ var FC = {
|
||||||
{bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true},
|
{bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true},
|
||||||
{bit: 28, group: 'other', name: 'PWM_OUTPUT_ENABLE', haveTip: true},
|
{bit: 28, group: 'other', name: 'PWM_OUTPUT_ENABLE', haveTip: true},
|
||||||
{bit: 26, group: 'other', name: 'SOFTSPI'},
|
{bit: 26, group: 'other', name: 'SOFTSPI'},
|
||||||
{bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true},
|
|
||||||
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false},
|
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false},
|
||||||
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false},
|
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false},
|
||||||
{bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false},
|
{bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false},
|
||||||
|
@ -607,12 +616,8 @@ var FC = {
|
||||||
getLooptimes: function () {
|
getLooptimes: function () {
|
||||||
return {
|
return {
|
||||||
125: {
|
125: {
|
||||||
defaultLooptime: 1000,
|
defaultLooptime: 500,
|
||||||
looptimes: {
|
looptimes: {
|
||||||
4000: "250Hz",
|
|
||||||
3000: "334Hz",
|
|
||||||
2000: "500Hz",
|
|
||||||
1500: "667Hz",
|
|
||||||
1000: "1kHz",
|
1000: "1kHz",
|
||||||
500: "2kHz",
|
500: "2kHz",
|
||||||
250: "4kHz",
|
250: "4kHz",
|
||||||
|
@ -622,8 +627,6 @@ var FC = {
|
||||||
1000: {
|
1000: {
|
||||||
defaultLooptime: 1000,
|
defaultLooptime: 1000,
|
||||||
looptimes: {
|
looptimes: {
|
||||||
4000: "250Hz",
|
|
||||||
2000: "500Hz",
|
|
||||||
1000: "1kHz"
|
1000: "1kHz"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -634,10 +637,6 @@ var FC = {
|
||||||
125: {
|
125: {
|
||||||
defaultLooptime: 1000,
|
defaultLooptime: 1000,
|
||||||
looptimes: {
|
looptimes: {
|
||||||
4000: "250Hz",
|
|
||||||
3000: "334Hz",
|
|
||||||
2000: "500Hz",
|
|
||||||
1500: "667Hz",
|
|
||||||
1000: "1kHz",
|
1000: "1kHz",
|
||||||
500: "2kHz",
|
500: "2kHz",
|
||||||
250: "4kHz",
|
250: "4kHz",
|
||||||
|
@ -647,8 +646,6 @@ var FC = {
|
||||||
1000: {
|
1000: {
|
||||||
defaultLooptime: 1000,
|
defaultLooptime: 1000,
|
||||||
looptimes: {
|
looptimes: {
|
||||||
4000: "250Hz",
|
|
||||||
2000: "500Hz",
|
|
||||||
1000: "1kHz"
|
1000: "1kHz"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -658,32 +655,26 @@ var FC = {
|
||||||
return [
|
return [
|
||||||
{
|
{
|
||||||
tick: 125,
|
tick: 125,
|
||||||
defaultDenominator: 16,
|
|
||||||
label: "256Hz"
|
label: "256Hz"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
tick: 1000,
|
tick: 1000,
|
||||||
defaultDenominator: 2,
|
|
||||||
label: "188Hz"
|
label: "188Hz"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
tick: 1000,
|
tick: 1000,
|
||||||
defaultDenominator: 2,
|
|
||||||
label: "98Hz"
|
label: "98Hz"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
tick: 1000,
|
tick: 1000,
|
||||||
defaultDenominator: 2,
|
|
||||||
label: "42Hz"
|
label: "42Hz"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
tick: 1000,
|
tick: 1000,
|
||||||
defaultDenominator: 2,
|
|
||||||
label: "20Hz"
|
label: "20Hz"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
tick: 1000,
|
tick: 1000,
|
||||||
defaultDenominator: 2,
|
|
||||||
label: "10Hz"
|
label: "10Hz"
|
||||||
}
|
}
|
||||||
];
|
];
|
||||||
|
@ -890,7 +881,11 @@ var FC = {
|
||||||
return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
|
return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
|
||||||
},
|
},
|
||||||
getOpticalFlowNames: function () {
|
getOpticalFlowNames: function () {
|
||||||
return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
|
if (semver.gte(CONFIG.flightControllerVersion, "2.7.0")) {
|
||||||
|
return [ "NONE", "CXOF", "MSP", "FAKE" ];
|
||||||
|
} else {
|
||||||
|
return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
|
||||||
|
}
|
||||||
},
|
},
|
||||||
getArmingFlags: function () {
|
getArmingFlags: function () {
|
||||||
return {
|
return {
|
||||||
|
@ -1134,6 +1129,11 @@ var FC = {
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
|
40: {
|
||||||
|
name: "MOD",
|
||||||
|
hasOperand: [true, true],
|
||||||
|
output: "raw"
|
||||||
|
},
|
||||||
18: {
|
18: {
|
||||||
name: "GVAR SET",
|
name: "GVAR SET",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
|
@ -1233,7 +1233,12 @@ var FC = {
|
||||||
name: "MAP OUTPUT",
|
name: "MAP OUTPUT",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
}
|
},
|
||||||
|
38: {
|
||||||
|
name: "RC CHANNEL OVERRIDE",
|
||||||
|
hasOperand: [true, true],
|
||||||
|
output: "boolean"
|
||||||
|
},
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
getOperandTypes: function () {
|
getOperandTypes: function () {
|
||||||
|
@ -1261,8 +1266,8 @@ var FC = {
|
||||||
1: "Home distance [m]",
|
1: "Home distance [m]",
|
||||||
2: "Trip distance [m]",
|
2: "Trip distance [m]",
|
||||||
3: "RSSI",
|
3: "RSSI",
|
||||||
4: "Vbat [deci-Volt] [1V = 10]",
|
4: "Vbat [centi-Volt] [1V = 100]",
|
||||||
5: "Cell voltage [deci-Volt] [1V = 10]",
|
5: "Cell voltage [centi-Volt] [1V = 100]",
|
||||||
6: "Current [centi-Amp] [1A = 100]",
|
6: "Current [centi-Amp] [1A = 100]",
|
||||||
7: "Current drawn [mAh]",
|
7: "Current drawn [mAh]",
|
||||||
8: "GPS Sats",
|
8: "GPS Sats",
|
||||||
|
@ -1291,6 +1296,7 @@ var FC = {
|
||||||
31: "3D home distance [m]",
|
31: "3D home distance [m]",
|
||||||
32: "CRSF LQ",
|
32: "CRSF LQ",
|
||||||
33: "CRSF SNR",
|
33: "CRSF SNR",
|
||||||
|
34: "GPS Valid Fix",
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
3: {
|
3: {
|
||||||
|
@ -1314,7 +1320,7 @@ var FC = {
|
||||||
4: {
|
4: {
|
||||||
name: "Logic Condition",
|
name: "Logic Condition",
|
||||||
type: "range",
|
type: "range",
|
||||||
range: [0, 15],
|
range: [0, 31],
|
||||||
default: 0
|
default: 0
|
||||||
},
|
},
|
||||||
5: {
|
5: {
|
||||||
|
@ -1322,6 +1328,12 @@ var FC = {
|
||||||
type: "range",
|
type: "range",
|
||||||
range: [0, 7],
|
range: [0, 7],
|
||||||
default: 0
|
default: 0
|
||||||
|
},
|
||||||
|
6: {
|
||||||
|
name: "Programming PID",
|
||||||
|
type: "range",
|
||||||
|
range: [0, 3],
|
||||||
|
default: 0
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -152,7 +152,7 @@ const mixerList = [
|
||||||
{
|
{
|
||||||
id: 8,
|
id: 8,
|
||||||
name: 'Flying Wing',
|
name: 'Flying Wing',
|
||||||
model: 'custom',
|
model: 'flying_wing',
|
||||||
image: 'flying_wing',
|
image: 'flying_wing',
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: true,
|
legacy: true,
|
||||||
|
@ -171,7 +171,7 @@ const mixerList = [
|
||||||
{
|
{
|
||||||
id: 27,
|
id: 27,
|
||||||
name: 'Flying Wing with differential thrust',
|
name: 'Flying Wing with differential thrust',
|
||||||
model: 'custom',
|
model: 'flying_wing',
|
||||||
image: 'flying_wing',
|
image: 'flying_wing',
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
|
|
|
@ -211,6 +211,9 @@ var MSPCodes = {
|
||||||
MSP2_INAV_SET_GLOBAL_FUNCTIONS: 0x2025,
|
MSP2_INAV_SET_GLOBAL_FUNCTIONS: 0x2025,
|
||||||
MSP2_INAV_LOGIC_CONDITIONS_STATUS: 0x2026,
|
MSP2_INAV_LOGIC_CONDITIONS_STATUS: 0x2026,
|
||||||
MSP2_INAV_GVAR_STATUS: 0x2027,
|
MSP2_INAV_GVAR_STATUS: 0x2027,
|
||||||
|
MSP2_INAV_PROGRAMMING_PID: 0x2028,
|
||||||
|
MSP2_INAV_SET_PROGRAMMING_PID: 0x2029,
|
||||||
|
MSP2_INAV_PROGRAMMING_PID_STATUS: 0x202A,
|
||||||
|
|
||||||
MSP2_PID: 0x2030,
|
MSP2_PID: 0x2030,
|
||||||
MSP2_SET_PID: 0x2031,
|
MSP2_SET_PID: 0x2031,
|
||||||
|
|
|
@ -43,6 +43,7 @@ var mspHelper = (function (gui) {
|
||||||
'FRSKY_OSD': 20,
|
'FRSKY_OSD': 20,
|
||||||
'DJI_FPV': 21,
|
'DJI_FPV': 21,
|
||||||
'SMARTPORT_MASTER': 23,
|
'SMARTPORT_MASTER': 23,
|
||||||
|
'IMU2': 24,
|
||||||
};
|
};
|
||||||
|
|
||||||
// Required for MSP_DEBUGMSG because console.log() doesn't allow omitting
|
// Required for MSP_DEBUGMSG because console.log() doesn't allow omitting
|
||||||
|
@ -539,6 +540,39 @@ var mspHelper = (function (gui) {
|
||||||
console.log("Logic conditions saved");
|
console.log("Logic conditions saved");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_PROGRAMMING_PID:
|
||||||
|
PROGRAMMING_PID.flush();
|
||||||
|
if (data.byteLength % 19 === 0) {
|
||||||
|
for (i = 0; i < data.byteLength; i += 19) {
|
||||||
|
PROGRAMMING_PID.put(new ProgrammingPid(
|
||||||
|
data.getInt8(i), // enabled
|
||||||
|
data.getInt8(i + 1), // setpointType
|
||||||
|
data.getInt32(i + 2, true), // setpointValue
|
||||||
|
data.getInt8(i + 6), // measurementType
|
||||||
|
data.getInt32(i + 7, true), // measurementValue
|
||||||
|
data.getInt16(i + 11, true), // gainP
|
||||||
|
data.getInt16(i + 13, true), // gainI
|
||||||
|
data.getInt16(i + 15, true), // gainD
|
||||||
|
data.getInt16(i + 17, true) // gainFF
|
||||||
|
));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS:
|
||||||
|
if (data.byteLength % 4 === 0) {
|
||||||
|
let index = 0;
|
||||||
|
for (i = 0; i < data.byteLength; i += 4) {
|
||||||
|
PROGRAMMING_PID_STATUS.set(index, data.getInt32(i, true));
|
||||||
|
index++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP2_INAV_SET_PROGRAMMING_PID:
|
||||||
|
console.log("Programming PID saved");
|
||||||
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP2_COMMON_MOTOR_MIXER:
|
case MSPCodes.MSP2_COMMON_MOTOR_MIXER:
|
||||||
MOTOR_RULES.flush();
|
MOTOR_RULES.flush();
|
||||||
|
|
||||||
|
@ -2349,6 +2383,58 @@ var mspHelper = (function (gui) {
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.loadProgrammingPid = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID, false, false, callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
self.sendProgrammingPid = function (onCompleteCallback) {
|
||||||
|
let nextFunction = sendPid,
|
||||||
|
pidIndex = 0;
|
||||||
|
|
||||||
|
if (PROGRAMMING_PID.getCount() == 0) {
|
||||||
|
onCompleteCallback();
|
||||||
|
} else {
|
||||||
|
nextFunction();
|
||||||
|
}
|
||||||
|
|
||||||
|
function sendPid() {
|
||||||
|
|
||||||
|
let buffer = [];
|
||||||
|
|
||||||
|
// send one at a time, with index, 20 bytes per one condition
|
||||||
|
|
||||||
|
let pid = PROGRAMMING_PID.get()[pidIndex];
|
||||||
|
|
||||||
|
buffer.push(pidIndex);
|
||||||
|
buffer.push(pid.getEnabled());
|
||||||
|
buffer.push(pid.getSetpointType());
|
||||||
|
buffer.push(specificByte(pid.getSetpointValue(), 0));
|
||||||
|
buffer.push(specificByte(pid.getSetpointValue(), 1));
|
||||||
|
buffer.push(specificByte(pid.getSetpointValue(), 2));
|
||||||
|
buffer.push(specificByte(pid.getSetpointValue(), 3));
|
||||||
|
buffer.push(pid.getMeasurementType());
|
||||||
|
buffer.push(specificByte(pid.getMeasurementValue(), 0));
|
||||||
|
buffer.push(specificByte(pid.getMeasurementValue(), 1));
|
||||||
|
buffer.push(specificByte(pid.getMeasurementValue(), 2));
|
||||||
|
buffer.push(specificByte(pid.getMeasurementValue(), 3));
|
||||||
|
buffer.push(specificByte(pid.getGainP(), 0));
|
||||||
|
buffer.push(specificByte(pid.getGainP(), 1));
|
||||||
|
buffer.push(specificByte(pid.getGainI(), 0));
|
||||||
|
buffer.push(specificByte(pid.getGainI(), 1));
|
||||||
|
buffer.push(specificByte(pid.getGainD(), 0));
|
||||||
|
buffer.push(specificByte(pid.getGainD(), 1));
|
||||||
|
buffer.push(specificByte(pid.getGainFF(), 0));
|
||||||
|
buffer.push(specificByte(pid.getGainFF(), 1));
|
||||||
|
|
||||||
|
// prepare for next iteration
|
||||||
|
pidIndex++;
|
||||||
|
if (pidIndex == PROGRAMMING_PID.getCount()) { //This is the last rule. Not pretty, but we have to send all rules
|
||||||
|
nextFunction = onCompleteCallback;
|
||||||
|
}
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_SET_PROGRAMMING_PID, buffer, false, nextFunction);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
self.sendModeRanges = function (onCompleteCallback) {
|
self.sendModeRanges = function (onCompleteCallback) {
|
||||||
var nextFunction = send_next_mode_range;
|
var nextFunction = send_next_mode_range;
|
||||||
|
|
||||||
|
@ -3227,5 +3313,13 @@ var mspHelper = (function (gui) {
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.loadProgrammingPidStatus = function (callback) {
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
|
||||||
|
} else {
|
||||||
|
callback();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
return self;
|
return self;
|
||||||
})(GUI);
|
})(GUI);
|
||||||
|
|
|
@ -97,14 +97,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -182,7 +174,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -204,10 +196,6 @@ presets.presets = [
|
||||||
{
|
{
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.500
|
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
type: 'multirotor'
|
type: 'multirotor'
|
||||||
|
@ -259,14 +247,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf_type",
|
key: "dterm_lpf_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -344,7 +324,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -366,10 +346,6 @@ presets.presets = [
|
||||||
{
|
{
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.850
|
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
type: 'multirotor'
|
type: 'multirotor'
|
||||||
|
@ -429,14 +405,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RPY"
|
value: "RPY"
|
||||||
|
@ -514,7 +482,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -536,10 +504,6 @@ presets.presets = [
|
||||||
{
|
{
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.800
|
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
type: 'multirotor'
|
type: 'multirotor'
|
||||||
|
@ -604,14 +568,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RPY"
|
value: "RPY"
|
||||||
|
@ -689,7 +645,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -712,10 +668,6 @@ presets.presets = [
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.300
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "heading_hold_rate_limit",
|
key: "heading_hold_rate_limit",
|
||||||
value: 30
|
value: 30
|
||||||
|
@ -786,14 +738,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "GYRO"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -871,7 +815,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -893,10 +837,6 @@ presets.presets = [
|
||||||
{
|
{
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.400
|
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
type: 'multirotor'
|
type: 'multirotor'
|
||||||
|
@ -956,14 +896,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -1041,7 +973,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -1063,10 +995,6 @@ presets.presets = [
|
||||||
{
|
{
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.850
|
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
type: 'multirotor'
|
type: 'multirotor'
|
||||||
|
@ -1126,14 +1054,6 @@ presets.presets = [
|
||||||
key: "dterm_lpf2_type",
|
key: "dterm_lpf2_type",
|
||||||
value: "PT1"
|
value: "PT1"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
key: "use_dterm_fir_filter",
|
|
||||||
value: "OFF"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "mc_iterm_relax_type",
|
|
||||||
value: "SETPOINT"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -1211,7 +1131,7 @@ presets.presets = [
|
||||||
value: 70
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "mc_airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -1233,401 +1153,340 @@ presets.presets = [
|
||||||
{
|
{
|
||||||
key: "throttle_idle",
|
key: "throttle_idle",
|
||||||
value: 12
|
value: 12
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "dterm_setpoint_weight",
|
|
||||||
value: 0.700
|
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
type: 'multirotor'
|
type: 'multirotor'
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: "Generic Airplane",
|
name: 'Airplane with a tail',
|
||||||
description: "General setup for airplanes.",
|
description: "General setup for airplanes with tails.",
|
||||||
features: [
|
features: ["Adjusted gyro filtering", "Adjusted PIDs", "Adjusted rates"],
|
||||||
"Adjusted gyro filtering",
|
|
||||||
"Adjusted PIDs",
|
|
||||||
"Adjusted rates"
|
|
||||||
],
|
|
||||||
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
||||||
settingsMSP: [
|
settingsMSP: [],
|
||||||
presets.elementHelper("RC_tuning", "roll_rate", 200),
|
type: 'airplane',
|
||||||
presets.elementHelper("RC_tuning", "pitch_rate", 150),
|
|
||||||
presets.elementHelper("RC_tuning", "yaw_rate", 90),
|
|
||||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 1)
|
|
||||||
],
|
|
||||||
settings: [
|
settings: [
|
||||||
{
|
{
|
||||||
key: "gyro_hardware_lpf",
|
|
||||||
value: "256HZ"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_hz",
|
|
||||||
value: 40
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_type",
|
|
||||||
value: "BIQUAD"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "platform_type",
|
key: "platform_type",
|
||||||
value: "AIRPLANE"
|
value: "AIRPLANE"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "rc_expo",
|
key: "applied_defaults",
|
||||||
value: 30
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "manual_rc_expo",
|
|
||||||
value: 30
|
|
||||||
}
|
|
||||||
],
|
|
||||||
type: 'airplane'
|
|
||||||
},
|
|
||||||
{
|
|
||||||
name: "Flying Wing Z84",
|
|
||||||
description: "Small flying wing on multirotor racer parts. 3S/4S battery, AUW under 500g.",
|
|
||||||
features: [
|
|
||||||
"Adjusted gyro filtering",
|
|
||||||
"Adjusted PIDs",
|
|
||||||
"Adjusted rates"
|
|
||||||
],
|
|
||||||
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
|
||||||
settingsMSP: [
|
|
||||||
presets.elementHelper("RC_tuning", "roll_rate", 350),
|
|
||||||
presets.elementHelper("RC_tuning", "pitch_rate", 90),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_PID", 33),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_breakpoint", 1300),
|
|
||||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 4)
|
|
||||||
],
|
|
||||||
settings: [
|
|
||||||
{
|
|
||||||
key: "gyro_hardware_lpf",
|
|
||||||
value: "256HZ"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_hz",
|
|
||||||
value: 40
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_type",
|
|
||||||
value: "BIQUAD"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "platform_type",
|
|
||||||
value: "AIRPLANE"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_pitch",
|
|
||||||
value: 2
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_pitch",
|
|
||||||
value: 15
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_pitch",
|
|
||||||
value: 70
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_roll",
|
|
||||||
value: 2
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_roll",
|
|
||||||
value: 15
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_roll",
|
|
||||||
value: 30
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "rc_expo",
|
|
||||||
value: 30
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "manual_rc_expo",
|
|
||||||
value: 30
|
|
||||||
}
|
|
||||||
],
|
|
||||||
type: 'flyingwing'
|
|
||||||
},
|
|
||||||
{
|
|
||||||
name: "Flying Wing S800 Sky Shadow",
|
|
||||||
description: "Flying wing on multirotor racer parts. 3S/4S battery and FPV equipment. AUW under 1000g.",
|
|
||||||
features: [
|
|
||||||
"Adjusted gyro filtering",
|
|
||||||
"Adjusted PIDs",
|
|
||||||
"Adjusted rates"
|
|
||||||
],
|
|
||||||
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
|
||||||
settingsMSP: [
|
|
||||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 0),
|
|
||||||
presets.elementHelper("FILTER_CONFIG", "gyroSoftLpfHz", 40),
|
|
||||||
presets.elementHelper("RC_tuning", "roll_rate", 280),
|
|
||||||
presets.elementHelper("RC_tuning", "pitch_rate", 140),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_PID", 20),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_breakpoint", 1600)
|
|
||||||
],
|
|
||||||
settings: [
|
|
||||||
{
|
|
||||||
key: "gyro_hardware_lpf",
|
|
||||||
value: "256HZ"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_hz",
|
|
||||||
value: 40
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_type",
|
|
||||||
value: "BIQUAD"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "platform_type",
|
|
||||||
value: "AIRPLANE"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_pitch",
|
|
||||||
value: 6
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_pitch",
|
|
||||||
value: 9
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_pitch",
|
|
||||||
value: 52
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_roll",
|
|
||||||
value: 6
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_roll",
|
|
||||||
value: 6
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_roll",
|
|
||||||
value: 49
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "rc_expo",
|
|
||||||
value: 30
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "manual_rc_expo",
|
|
||||||
value: 30
|
|
||||||
}
|
|
||||||
],
|
|
||||||
type: 'flyingwing'
|
|
||||||
},
|
|
||||||
{
|
|
||||||
name: "Ritewing Mini Drak",
|
|
||||||
description: "8x6 propeller, 2216 1400kV motor, 4S LiPo. AUW above 1200g.",
|
|
||||||
features: [
|
|
||||||
"Adjusted gyro filtering",
|
|
||||||
"Adjusted PIDs",
|
|
||||||
"Adjusted rates"
|
|
||||||
],
|
|
||||||
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
|
||||||
settingsMSP: [
|
|
||||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 0),
|
|
||||||
presets.elementHelper("FILTER_CONFIG", "gyroSoftLpfHz", 35),
|
|
||||||
presets.elementHelper("RC_tuning", "roll_rate", 260),
|
|
||||||
presets.elementHelper("RC_tuning", "pitch_rate", 140),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_PID", 30),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_breakpoint", 1550)
|
|
||||||
],
|
|
||||||
settings: [
|
|
||||||
{
|
|
||||||
key: "gyro_hardware_lpf",
|
|
||||||
value: "256HZ"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_hz",
|
|
||||||
value: 40
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_type",
|
|
||||||
value: "BIQUAD"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "platform_type",
|
|
||||||
value: "AIRPLANE"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_pitch",
|
|
||||||
value: 5
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_pitch",
|
|
||||||
value: 14
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_pitch",
|
|
||||||
value: 56
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_roll",
|
|
||||||
value: 7
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_roll",
|
|
||||||
value: 12
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_roll",
|
|
||||||
value: 25
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "rc_expo",
|
|
||||||
value: 30
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "manual_rc_expo",
|
|
||||||
value: 30
|
|
||||||
}
|
|
||||||
],
|
|
||||||
type: 'flyingwing'
|
|
||||||
},
|
|
||||||
{
|
|
||||||
name: "ZOHD Dart 250g",
|
|
||||||
description: "3x5x3 propeller, 1406 2600kV motor, 3S LiPo. 570mm wingspan, AUW potentially under 250g on 2S.<br /><br /><strong>Please set the Stabilised Roll weight to 80, and the Stabilised Pitch weight to 65.</strong>",
|
|
||||||
features: [
|
|
||||||
"Adjusted gyro filtering",
|
|
||||||
"Adjusted PIDs",
|
|
||||||
"Adjusted rates"
|
|
||||||
],
|
|
||||||
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
|
||||||
settingsMSP: [
|
|
||||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 3),
|
|
||||||
presets.elementHelper("FILTER_CONFIG", "gyroSoftLpfHz", 30),
|
|
||||||
presets.elementHelper("RC_tuning", "roll_rate", 360),
|
|
||||||
presets.elementHelper("RC_tuning", "pitch_rate", 130),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_PID", 30),
|
|
||||||
presets.elementHelper("RC_tuning", "dynamic_THR_breakpoint", 1500)
|
|
||||||
],
|
|
||||||
settings: [
|
|
||||||
{
|
|
||||||
key: "gyro_hardware_lpf",
|
|
||||||
value: "256HZ"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_hz",
|
|
||||||
value: 40
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "gyro_lpf_type",
|
|
||||||
value: "BIQUAD"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "platform_type",
|
|
||||||
value: "AIRPLANE"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_pitch",
|
|
||||||
value: 3
|
value: 3
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_i_pitch",
|
|
||||||
value: 7
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_pitch",
|
|
||||||
value: 40
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_p_roll",
|
|
||||||
value: 2
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_i_roll",
|
|
||||||
value: 4
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "fw_ff_roll",
|
|
||||||
value: 18
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "rc_expo",
|
|
||||||
value: 70
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "manual_rc_expo",
|
|
||||||
value: 70
|
|
||||||
},
|
|
||||||
{
|
|
||||||
key: "rc_yaw_expo",
|
|
||||||
value: 20
|
|
||||||
}
|
|
||||||
],
|
|
||||||
type: 'flyingwing'
|
|
||||||
},
|
|
||||||
{
|
|
||||||
name: "SonicModell Mini AR Wing",
|
|
||||||
description: "5x4.5 propeller, 1805 2400kV motor, 3S LiPo. 600mm wingspan, AUW under 400g.",
|
|
||||||
features: [
|
|
||||||
"Adjusted gyro filtering",
|
|
||||||
"Adjusted PIDs",
|
|
||||||
"Adjusted rates"
|
|
||||||
],
|
|
||||||
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
|
||||||
settingsMSP: [
|
|
||||||
presets.elementHelper("INAV_PID_CONFIG", "gyroscopeLpf", 0),
|
|
||||||
presets.elementHelper("FILTER_CONFIG", "gyroSoftLpfHz", 35),
|
|
||||||
presets.elementHelper("RC_tuning", "roll_rate", 280),
|
|
||||||
presets.elementHelper("RC_tuning", "pitch_rate", 120)
|
|
||||||
],
|
|
||||||
settings: [
|
|
||||||
{
|
|
||||||
key: "gyro_hardware_lpf",
|
key: "gyro_hardware_lpf",
|
||||||
value: "256HZ"
|
value: "256HZ"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "gyro_lpf_hz",
|
key: "gyro_lpf_hz",
|
||||||
value: 40
|
value: 25
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
key: "dterm_lpf_hz",
|
||||||
|
value: 40
|
||||||
|
},
|
||||||
|
{
|
||||||
key: "gyro_lpf_type",
|
key: "gyro_lpf_type",
|
||||||
value: "BIQUAD"
|
value: "BIQUAD"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "platform_type",
|
key: "dynamic_gyro_notch_enabled",
|
||||||
value: "AIRPLANE"
|
value: "ON"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_p_pitch",
|
key: "dynamic_gyro_notch_q",
|
||||||
value: 5
|
value: 250
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_i_pitch",
|
key: "dynamic_gyro_notch_min_hz",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "motor_pwm_protocol",
|
||||||
|
value: "STANDARD"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "throttle_idle",
|
||||||
|
value: 5.0
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "rc_yaw_expo",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "rc_expo",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "roll_rate",
|
||||||
value: 18
|
value: 18
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
key: "pitch_rate",
|
||||||
|
value: 9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "yaw_rate",
|
||||||
|
value: 3
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_p",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_d",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_xy_p",
|
||||||
|
value: 50
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_turn_assist_pitch_gain",
|
||||||
|
value: 0.5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "max_angle_inclination_rll",
|
||||||
|
value: 350
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_bank_angle",
|
||||||
|
value: 35
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_pitch",
|
||||||
|
value: 15
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_pitch",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
key: "fw_ff_pitch",
|
key: "fw_ff_pitch",
|
||||||
value: 60
|
value: 60
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_p_roll",
|
key: "fw_p_roll",
|
||||||
value: 8
|
value: 10
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_i_roll",
|
key: "fw_i_roll",
|
||||||
value: 16
|
value: 8
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_ff_roll",
|
key: "fw_ff_roll",
|
||||||
value: 64
|
value: 40
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
key: "fw_p_yaw",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_yaw",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_yaw",
|
||||||
|
value: 100
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_acc_ignore_rate",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "airmode_type",
|
||||||
|
value: "STICK_CENTER_ONCE"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "small_angle",
|
||||||
|
value: 180
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_control_smoothness",
|
||||||
|
value: 2
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_rth_allow_landing",
|
||||||
|
value: "FS_ONLY"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_rth_altitude",
|
||||||
|
value: 5000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "failsafe_mission",
|
||||||
|
value: "ON"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_wp_radius",
|
||||||
|
value: 1500
|
||||||
|
},
|
||||||
|
],
|
||||||
|
},
|
||||||
|
{
|
||||||
|
name: "Airplane without tail",
|
||||||
|
description: "General setup for airplanes without tails: Flying Wing, Delta, etc.",
|
||||||
|
features: ["Adjusted gyro filtering", "Adjusted PIDs", "Adjusted rates"],
|
||||||
|
applyDefaults: ["INAV_PID_CONFIG", "RC_tuning", "PID_ADVANCED", "FILTER_CONFIG"],
|
||||||
|
settingsMSP: [],
|
||||||
|
type: 'flyingwing',
|
||||||
|
settings: [
|
||||||
|
{
|
||||||
|
key: "platform_type",
|
||||||
|
value: "AIRPLANE"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "applied_defaults",
|
||||||
|
value: 3
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "gyro_hardware_lpf",
|
||||||
|
value: "256HZ"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "gyro_lpf_hz",
|
||||||
|
value: 25
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dterm_lpf_hz",
|
||||||
|
value: 40
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "gyro_lpf_type",
|
||||||
|
value: "BIQUAD"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_enabled",
|
||||||
|
value: "ON"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_q",
|
||||||
|
value: 250
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "dynamic_gyro_notch_min_hz",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "motor_pwm_protocol",
|
||||||
|
value: "STANDARD"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "throttle_idle",
|
||||||
|
value: 5.0
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "rc_yaw_expo",
|
||||||
|
value: 30
|
||||||
|
},
|
||||||
|
{
|
||||||
key: "rc_expo",
|
key: "rc_expo",
|
||||||
value: 30
|
value: 30
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "manual_rc_expo",
|
key: "roll_rate",
|
||||||
value: 30
|
value: 18
|
||||||
}
|
},
|
||||||
],
|
{
|
||||||
type: 'flyingwing'
|
key: "pitch_rate",
|
||||||
}
|
value: 9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "yaw_rate",
|
||||||
|
value: 3
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_p",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_d",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_xy_p",
|
||||||
|
value: 50
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_turn_assist_pitch_gain",
|
||||||
|
value: 0.2
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "max_angle_inclination_rll",
|
||||||
|
value: 450
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_bank_angle",
|
||||||
|
value: 45
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_pitch",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_pitch",
|
||||||
|
value: 15
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_pitch",
|
||||||
|
value: 70
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_roll",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_roll",
|
||||||
|
value: 8
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_roll",
|
||||||
|
value: 35
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_p_yaw",
|
||||||
|
value: 20
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_i_yaw",
|
||||||
|
value: 5
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "fw_ff_yaw",
|
||||||
|
value: 100
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_acc_ignore_rate",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "airmode_type",
|
||||||
|
value: "STICK_CENTER_ONCE"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "small_angle",
|
||||||
|
value: 180
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_control_smoothness",
|
||||||
|
value: 2
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_rth_allow_landing",
|
||||||
|
value: "FS_ONLY"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_rth_altitude",
|
||||||
|
value: 5000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "failsafe_mission",
|
||||||
|
value: "ON"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_wp_radius",
|
||||||
|
value: 1500
|
||||||
|
},
|
||||||
|
],
|
||||||
|
},
|
||||||
];
|
];
|
||||||
|
|
224
js/programmingPid.js
Normal file
224
js/programmingPid.js
Normal file
|
@ -0,0 +1,224 @@
|
||||||
|
/*global $,FC*/
|
||||||
|
'use strict';
|
||||||
|
|
||||||
|
let ProgrammingPid = function (enabled, setpointType, setpointValue, measurementType, measurementValue, gainP, gainI, gainD, gainFF) {
|
||||||
|
let self = {};
|
||||||
|
let $row;
|
||||||
|
|
||||||
|
self.getEnabled = function () {
|
||||||
|
return !!enabled;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setEnabled = function (data) {
|
||||||
|
enabled = !!data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getSetpointType = function () {
|
||||||
|
return setpointType;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setSetpointType = function (data) {
|
||||||
|
setpointType = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getSetpointValue = function () {
|
||||||
|
return setpointValue;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setSetpointValue = function (data) {
|
||||||
|
setpointValue = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getMeasurementType = function () {
|
||||||
|
return measurementType;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setMeasurementType = function (data) {
|
||||||
|
measurementType = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getMeasurementValue = function () {
|
||||||
|
return measurementValue;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setMeasurementValue = function (data) {
|
||||||
|
measurementValue = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getGainP = function () {
|
||||||
|
return gainP;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setGainP = function (data) {
|
||||||
|
gainP = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getGainI = function () {
|
||||||
|
return gainI;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setGainI = function (data) {
|
||||||
|
gainI = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getGainD = function () {
|
||||||
|
return gainD;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setGainD = function (data) {
|
||||||
|
gainD = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getGainFF = function () {
|
||||||
|
return gainFF;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.setGainFF = function (data) {
|
||||||
|
gainFF = data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.onEnabledChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget);
|
||||||
|
self.setEnabled(!!$cT.prop('checked'));
|
||||||
|
};
|
||||||
|
|
||||||
|
self.onGainPChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget);
|
||||||
|
self.setGainP($cT.val());
|
||||||
|
};
|
||||||
|
|
||||||
|
self.onGainIChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget);
|
||||||
|
self.setGainI($cT.val());
|
||||||
|
};
|
||||||
|
|
||||||
|
self.onGainDChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget);
|
||||||
|
self.setGainD($cT.val());
|
||||||
|
};
|
||||||
|
|
||||||
|
self.onGainFFChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget);
|
||||||
|
self.setGainFF($cT.val());
|
||||||
|
};
|
||||||
|
|
||||||
|
self.onOperatorValueChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget),
|
||||||
|
operand = $cT.data("operand");
|
||||||
|
|
||||||
|
if (operand == 0) {
|
||||||
|
self.setSetpointValue($cT.val());
|
||||||
|
} else {
|
||||||
|
self.setMeasurementValue($cT.val());
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
self.render = function (index, $container) {
|
||||||
|
|
||||||
|
$container.find('tbody').append('<tr>\
|
||||||
|
<td class="pid_cell__index"></td>\
|
||||||
|
<td class="pid_cell__enabled"></td>\
|
||||||
|
<td class="pid_cell__setpoint"></td>\
|
||||||
|
<td class="pid_cell__measurement"></td>\
|
||||||
|
<td class="pid_cell__p"></td>\
|
||||||
|
<td class="pid_cell__i"></td>\
|
||||||
|
<td class="pid_cell__d"></td>\
|
||||||
|
<td class="pid_cell__ff"></td>\
|
||||||
|
<td class="pid_cell__output"></td>\
|
||||||
|
</tr>\
|
||||||
|
');
|
||||||
|
|
||||||
|
$row = $container.find('tr:last');
|
||||||
|
|
||||||
|
$row.find('.pid_cell__index').html(index);
|
||||||
|
$row.find('.pid_cell__enabled').html("<input type='checkbox' class='toggle logic_element__enabled' />");
|
||||||
|
$row.find('.logic_element__enabled').
|
||||||
|
prop('checked', self.getEnabled()).
|
||||||
|
change(self.onEnabledChange);
|
||||||
|
|
||||||
|
self.renderOperand(0);
|
||||||
|
self.renderOperand(1);
|
||||||
|
|
||||||
|
$row.find(".pid_cell__p").html('<input type="number" class="pid_cell__p-gain" step="1" min="0" max="32767" value="0">');
|
||||||
|
$row.find(".pid_cell__p-gain").val(self.getGainP()).change(self.onGainPChange);
|
||||||
|
|
||||||
|
$row.find(".pid_cell__i").html('<input type="number" class="pid_cell__i-gain" step="1" min="0" max="32767" value="0">');
|
||||||
|
$row.find(".pid_cell__i-gain").val(self.getGainI()).change(self.onGainIChange);
|
||||||
|
|
||||||
|
$row.find(".pid_cell__d").html('<input type="number" class="pid_cell__d-gain" step="1" min="0" max="32767" value="0">');
|
||||||
|
$row.find(".pid_cell__d-gain").val(self.getGainD()).change(self.onGainDChange);
|
||||||
|
|
||||||
|
$row.find(".pid_cell__ff").html('<input type="number" class="pid_cell__ff-gain" step="1" min="0" max="32767" value="0">');
|
||||||
|
$row.find(".pid_cell__ff-gain").val(self.getGainFF()).change(self.onGainFFChange);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
self.onOperatorTypeChange = function (event) {
|
||||||
|
let $cT = $(event.currentTarget),
|
||||||
|
operand = $cT.data("operand"),
|
||||||
|
$container = $cT.parent(),
|
||||||
|
operandMetadata = FC.getOperandTypes()[$cT.val()];
|
||||||
|
|
||||||
|
if (operand == 0) {
|
||||||
|
self.setSetpointType($cT.val());
|
||||||
|
self.setSetpointValue(operandMetadata.default);
|
||||||
|
} else {
|
||||||
|
self.setMeasurementType($cT.val());
|
||||||
|
self.setMeasurementValue(operandMetadata.default);
|
||||||
|
}
|
||||||
|
|
||||||
|
GUI.renderOperandValue($container, operandMetadata, operand, operandMetadata.default, self.onOperatorValueChange);
|
||||||
|
};
|
||||||
|
|
||||||
|
self.renderOperand = function (operand) {
|
||||||
|
let type, value, $container;
|
||||||
|
if (operand == 0) {
|
||||||
|
type = setpointType;
|
||||||
|
value = setpointValue;
|
||||||
|
$container = $row.find('.pid_cell__setpoint');
|
||||||
|
} else {
|
||||||
|
type = measurementType;
|
||||||
|
value = measurementValue;
|
||||||
|
$container = $row.find('.pid_cell__measurement');
|
||||||
|
}
|
||||||
|
|
||||||
|
$container.html('');
|
||||||
|
|
||||||
|
$container.append('<select class="logic_element__operand--type" data-operand="' + operand + '"></select>');
|
||||||
|
let $t = $container.find('.logic_element__operand--type');
|
||||||
|
|
||||||
|
for (let k in FC.getOperandTypes()) {
|
||||||
|
if (FC.getOperandTypes().hasOwnProperty(k)) {
|
||||||
|
let op = FC.getOperandTypes()[k];
|
||||||
|
|
||||||
|
if (type == k) {
|
||||||
|
$t.append('<option value="' + k + '" selected>' + op.name + '</option>');
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Render value element depending on type
|
||||||
|
*/
|
||||||
|
GUI.renderOperandValue($container, op, operand, value, self.onOperatorValueChange);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
$t.append('<option value="' + k + '">' + op.name + '</option>');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Bind events
|
||||||
|
*/
|
||||||
|
$t.change(self.onOperatorTypeChange);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
self.update = function (index, value, $container) {
|
||||||
|
if (typeof $row === 'undefined') {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
$row.find('.pid_cell__output').html(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
return self;
|
||||||
|
};
|
58
js/programmingPidCollection.js
Normal file
58
js/programmingPidCollection.js
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
'use strict';
|
||||||
|
|
||||||
|
let ProgrammingPidCollection = function () {
|
||||||
|
|
||||||
|
let self = {},
|
||||||
|
data = [],
|
||||||
|
$container;
|
||||||
|
|
||||||
|
self.put = function (element) {
|
||||||
|
data.push(element);
|
||||||
|
};
|
||||||
|
|
||||||
|
self.get = function () {
|
||||||
|
return data;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.flush = function () {
|
||||||
|
data = [];
|
||||||
|
};
|
||||||
|
|
||||||
|
self.getCount = function () {
|
||||||
|
return data.length
|
||||||
|
};
|
||||||
|
|
||||||
|
self.open = function () {
|
||||||
|
self.render();
|
||||||
|
$container.show();
|
||||||
|
};
|
||||||
|
|
||||||
|
self.init = function ($element) {
|
||||||
|
$container = $element;
|
||||||
|
};
|
||||||
|
|
||||||
|
self.render = function () {
|
||||||
|
let $table = $container.find(".pid__table")
|
||||||
|
$table.find("tbody tr").remove();
|
||||||
|
|
||||||
|
for (let k in self.get()) {
|
||||||
|
if (self.get().hasOwnProperty(k)) {
|
||||||
|
self.get()[k].render(k, $table);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
GUI.switchery();
|
||||||
|
};
|
||||||
|
|
||||||
|
self.update = function(statuses) {
|
||||||
|
let $table = $container.find(".pid__table")
|
||||||
|
|
||||||
|
for (let k in self.get()) {
|
||||||
|
if (self.get().hasOwnProperty(k)) {
|
||||||
|
self.get()[k].update(k, statuses.get(k), $table);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return self;
|
||||||
|
};
|
33
js/programmingPidStatus.js
Normal file
33
js/programmingPidStatus.js
Normal file
|
@ -0,0 +1,33 @@
|
||||||
|
'use strict';
|
||||||
|
|
||||||
|
let ProgrammingPidStatus = function () {
|
||||||
|
|
||||||
|
let self = {},
|
||||||
|
data = [];
|
||||||
|
|
||||||
|
self.set = function (condition, value) {
|
||||||
|
data[condition] = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
self.get = function (condition) {
|
||||||
|
if (typeof data[condition] !== 'undefined') {
|
||||||
|
return data[condition];
|
||||||
|
} else {
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
self.getAll = function() {
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
self.update = function ($container) {
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
self.init = function ($container) {
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return self;
|
||||||
|
};
|
2
main.css
2
main.css
|
@ -2107,7 +2107,7 @@ select {
|
||||||
}
|
}
|
||||||
|
|
||||||
.info-box {
|
.info-box {
|
||||||
background-color: darkgoldenrod;
|
background-color: #37a8db;
|
||||||
color: white;
|
color: white;
|
||||||
font-weight: bold;
|
font-weight: bold;
|
||||||
margin: 0.4em 0;
|
margin: 0.4em 0;
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
{
|
{
|
||||||
"manifest_version": 2,
|
"manifest_version": 2,
|
||||||
"minimum_chrome_version": "38",
|
"minimum_chrome_version": "38",
|
||||||
"version": "2.7.0",
|
"version": "3.0.0",
|
||||||
"author": "Several",
|
"author": "Several",
|
||||||
"name": "INAV - Configurator",
|
"name": "INAV - Configurator",
|
||||||
"short_name": "INAV",
|
"short_name": "INAV",
|
||||||
|
|
72
package-lock.json
generated
72
package-lock.json
generated
|
@ -1,7 +1,7 @@
|
||||||
{
|
{
|
||||||
"name": "inav-configurator",
|
"name": "inav-configurator",
|
||||||
"version": "2.7.0",
|
"version": "2.7.0",
|
||||||
"lockfileVersion": 2,
|
"lockfileVersion": 1,
|
||||||
"requires": true,
|
"requires": true,
|
||||||
"packages": {
|
"packages": {
|
||||||
"": {
|
"": {
|
||||||
|
@ -8702,7 +8702,6 @@
|
||||||
"version": "0.1.4",
|
"version": "0.1.4",
|
||||||
"resolved": "https://registry.npmjs.org/align-text/-/align-text-0.1.4.tgz",
|
"resolved": "https://registry.npmjs.org/align-text/-/align-text-0.1.4.tgz",
|
||||||
"integrity": "sha1-DNkKVhCT810KmSVsIrcGlDP60Rc=",
|
"integrity": "sha1-DNkKVhCT810KmSVsIrcGlDP60Rc=",
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"kind-of": "^3.0.2",
|
"kind-of": "^3.0.2",
|
||||||
"longest": "^1.0.1",
|
"longest": "^1.0.1",
|
||||||
|
@ -8713,7 +8712,6 @@
|
||||||
"version": "3.2.2",
|
"version": "3.2.2",
|
||||||
"resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz",
|
"resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz",
|
||||||
"integrity": "sha1-MeohpzS6ubuw8yRm2JOupR5KPGQ=",
|
"integrity": "sha1-MeohpzS6ubuw8yRm2JOupR5KPGQ=",
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"is-buffer": "^1.1.5"
|
"is-buffer": "^1.1.5"
|
||||||
}
|
}
|
||||||
|
@ -10859,10 +10857,7 @@
|
||||||
},
|
},
|
||||||
"ansi-regex": {
|
"ansi-regex": {
|
||||||
"version": "2.1.1",
|
"version": "2.1.1",
|
||||||
"resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-2.1.1.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-w7M6te42DYbg5ijwRorn7yfWVN8=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"aproba": {
|
"aproba": {
|
||||||
"version": "1.2.0",
|
"version": "1.2.0",
|
||||||
|
@ -10884,17 +10879,13 @@
|
||||||
},
|
},
|
||||||
"balanced-match": {
|
"balanced-match": {
|
||||||
"version": "1.0.0",
|
"version": "1.0.0",
|
||||||
"resolved": "https://registry.npmjs.org/balanced-match/-/balanced-match-1.0.0.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-ibTRmasr7kneFk6gK4nORi1xt2c=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"brace-expansion": {
|
"brace-expansion": {
|
||||||
"version": "1.1.11",
|
"version": "1.1.11",
|
||||||
"resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.11.tgz",
|
"resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.11.tgz",
|
||||||
"integrity": "sha512-iCuPHDFgrHX7H2vEI/5xpz07zSHB00TpugqhmYtVmMO6518mCuRMoOYFldEBl0g187ufozdaHgWKcYFb61qGiA==",
|
"integrity": "sha512-iCuPHDFgrHX7H2vEI/5xpz07zSHB00TpugqhmYtVmMO6518mCuRMoOYFldEBl0g187ufozdaHgWKcYFb61qGiA==",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"balanced-match": "^1.0.0",
|
"balanced-match": "^1.0.0",
|
||||||
"concat-map": "0.0.1"
|
"concat-map": "0.0.1"
|
||||||
|
@ -10909,24 +10900,15 @@
|
||||||
},
|
},
|
||||||
"code-point-at": {
|
"code-point-at": {
|
||||||
"version": "1.1.0",
|
"version": "1.1.0",
|
||||||
"resolved": "https://registry.npmjs.org/code-point-at/-/code-point-at-1.1.0.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-DQcLTQQ6W+ozovGkDi7bPZpMz3c=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"concat-map": {
|
"concat-map": {
|
||||||
"version": "0.0.1",
|
"version": "0.0.1",
|
||||||
"resolved": "https://registry.npmjs.org/concat-map/-/concat-map-0.0.1.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-2Klr13/Wjfd5OnMDajug1UBdR3s=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"console-control-strings": {
|
"console-control-strings": {
|
||||||
"version": "1.1.0",
|
"version": "1.1.0",
|
||||||
"resolved": "https://registry.npmjs.org/console-control-strings/-/console-control-strings-1.1.0.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-PXz0Rk22RG6mRL9LOVB/mFEAjo4=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"core-util-is": {
|
"core-util-is": {
|
||||||
"version": "1.0.2",
|
"version": "1.0.2",
|
||||||
|
@ -11055,10 +11037,7 @@
|
||||||
},
|
},
|
||||||
"inherits": {
|
"inherits": {
|
||||||
"version": "2.0.3",
|
"version": "2.0.3",
|
||||||
"resolved": "https://registry.npmjs.org/inherits/-/inherits-2.0.3.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-Yzwsg+PaQqUC9SRmAiSA9CCCYd4=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"ini": {
|
"ini": {
|
||||||
"version": "1.3.5",
|
"version": "1.3.5",
|
||||||
|
@ -11072,7 +11051,6 @@
|
||||||
"resolved": "https://registry.npmjs.org/is-fullwidth-code-point/-/is-fullwidth-code-point-1.0.0.tgz",
|
"resolved": "https://registry.npmjs.org/is-fullwidth-code-point/-/is-fullwidth-code-point-1.0.0.tgz",
|
||||||
"integrity": "sha1-754xOG8DGn8NZDr4L95QxFfvAMs=",
|
"integrity": "sha1-754xOG8DGn8NZDr4L95QxFfvAMs=",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"number-is-nan": "^1.0.0"
|
"number-is-nan": "^1.0.0"
|
||||||
}
|
}
|
||||||
|
@ -11089,24 +11067,19 @@
|
||||||
"resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.0.4.tgz",
|
"resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.0.4.tgz",
|
||||||
"integrity": "sha512-yJHVQEhyqPLUTgt9B83PXu6W3rx4MvvHvSUvToogpwoGDOUQ+yDrR0HRot+yOCdCO7u4hX3pWft6kWBBcqh0UA==",
|
"integrity": "sha512-yJHVQEhyqPLUTgt9B83PXu6W3rx4MvvHvSUvToogpwoGDOUQ+yDrR0HRot+yOCdCO7u4hX3pWft6kWBBcqh0UA==",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"brace-expansion": "^1.1.7"
|
"brace-expansion": "^1.1.7"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"minimist": {
|
"minimist": {
|
||||||
"version": "0.0.8",
|
"version": "0.0.8",
|
||||||
"resolved": "https://registry.npmjs.org/minimist/-/minimist-0.0.8.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-hX/Kv8M5fSYluCKCYuhqp6ARsF0=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"minipass": {
|
"minipass": {
|
||||||
"version": "2.3.5",
|
"version": "2.3.5",
|
||||||
"resolved": "https://registry.npmjs.org/minipass/-/minipass-2.3.5.tgz",
|
"resolved": "https://registry.npmjs.org/minipass/-/minipass-2.3.5.tgz",
|
||||||
"integrity": "sha512-Gi1W4k059gyRbyVUZQ4mEqLm0YIUiGYfvxhF6SIlk3ui1WVxMTGfGdQ2SInh3PDrRTVvPKgULkpJtT4RH10+VA==",
|
"integrity": "sha512-Gi1W4k059gyRbyVUZQ4mEqLm0YIUiGYfvxhF6SIlk3ui1WVxMTGfGdQ2SInh3PDrRTVvPKgULkpJtT4RH10+VA==",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"safe-buffer": "^5.1.2",
|
"safe-buffer": "^5.1.2",
|
||||||
"yallist": "^3.0.0"
|
"yallist": "^3.0.0"
|
||||||
|
@ -11127,7 +11100,6 @@
|
||||||
"resolved": "https://registry.npmjs.org/mkdirp/-/mkdirp-0.5.1.tgz",
|
"resolved": "https://registry.npmjs.org/mkdirp/-/mkdirp-0.5.1.tgz",
|
||||||
"integrity": "sha1-MAV0OOrGz3+MR2fzhkjWaX11yQM=",
|
"integrity": "sha1-MAV0OOrGz3+MR2fzhkjWaX11yQM=",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"minimist": "0.0.8"
|
"minimist": "0.0.8"
|
||||||
}
|
}
|
||||||
|
@ -11214,10 +11186,7 @@
|
||||||
},
|
},
|
||||||
"number-is-nan": {
|
"number-is-nan": {
|
||||||
"version": "1.0.1",
|
"version": "1.0.1",
|
||||||
"resolved": "https://registry.npmjs.org/number-is-nan/-/number-is-nan-1.0.1.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-CXtgK1NCKlIsGvuHkDGDNpQaAR0=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"object-assign": {
|
"object-assign": {
|
||||||
"version": "4.1.1",
|
"version": "4.1.1",
|
||||||
|
@ -11231,7 +11200,6 @@
|
||||||
"resolved": "https://registry.npmjs.org/once/-/once-1.4.0.tgz",
|
"resolved": "https://registry.npmjs.org/once/-/once-1.4.0.tgz",
|
||||||
"integrity": "sha1-WDsap3WWHUsROsF9nFC6753Xa9E=",
|
"integrity": "sha1-WDsap3WWHUsROsF9nFC6753Xa9E=",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"wrappy": "1"
|
"wrappy": "1"
|
||||||
}
|
}
|
||||||
|
@ -11325,10 +11293,7 @@
|
||||||
},
|
},
|
||||||
"safe-buffer": {
|
"safe-buffer": {
|
||||||
"version": "5.1.2",
|
"version": "5.1.2",
|
||||||
"resolved": "https://registry.npmjs.org/safe-buffer/-/safe-buffer-5.1.2.tgz",
|
"bundled": true
|
||||||
"integrity": "sha512-Gd2UZBJDkXlY7GbJxfsE8/nvKkUEU1G38c1siN6QP6a9PT9MmHB8GnpscSmMJSoF8LOIrt8ud/wPtojys4G6+g==",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"safer-buffer": {
|
"safer-buffer": {
|
||||||
"version": "2.1.2",
|
"version": "2.1.2",
|
||||||
|
@ -11370,7 +11335,6 @@
|
||||||
"resolved": "https://registry.npmjs.org/string_decoder/-/string_decoder-1.1.1.tgz",
|
"resolved": "https://registry.npmjs.org/string_decoder/-/string_decoder-1.1.1.tgz",
|
||||||
"integrity": "sha512-n/ShnvDi6FHbbVfviro+WojiFzv+s8MPMHBczVePfUpDJLwoLT0ht1l4YwBCbi8pJAveEEdnkHyPyTP/mzRfwg==",
|
"integrity": "sha512-n/ShnvDi6FHbbVfviro+WojiFzv+s8MPMHBczVePfUpDJLwoLT0ht1l4YwBCbi8pJAveEEdnkHyPyTP/mzRfwg==",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"safe-buffer": "~5.1.0"
|
"safe-buffer": "~5.1.0"
|
||||||
}
|
}
|
||||||
|
@ -11392,7 +11356,6 @@
|
||||||
"resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-3.0.1.tgz",
|
"resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-3.0.1.tgz",
|
||||||
"integrity": "sha1-ajhfuIU9lS1f8F0Oiq+UJ43GPc8=",
|
"integrity": "sha1-ajhfuIU9lS1f8F0Oiq+UJ43GPc8=",
|
||||||
"bundled": true,
|
"bundled": true,
|
||||||
"optional": true,
|
|
||||||
"requires": {
|
"requires": {
|
||||||
"ansi-regex": "^2.0.0"
|
"ansi-regex": "^2.0.0"
|
||||||
}
|
}
|
||||||
|
@ -11439,17 +11402,11 @@
|
||||||
},
|
},
|
||||||
"wrappy": {
|
"wrappy": {
|
||||||
"version": "1.0.2",
|
"version": "1.0.2",
|
||||||
"resolved": "https://registry.npmjs.org/wrappy/-/wrappy-1.0.2.tgz",
|
"bundled": true
|
||||||
"integrity": "sha1-tSQ9jz7BqjXxNkYFvA0QNuMKtp8=",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"yallist": {
|
"yallist": {
|
||||||
"version": "3.0.3",
|
"version": "3.0.3",
|
||||||
"resolved": "https://registry.npmjs.org/yallist/-/yallist-3.0.3.tgz",
|
"bundled": true
|
||||||
"integrity": "sha512-S+Zk8DEWE6oKpV+vI3qWkaK+jSbIK86pCwe2IF/xwIpQ8jEuxpw9NyaGjmp9+BoJv5FV2piqCDcoCtStppiq2A==",
|
|
||||||
"bundled": true,
|
|
||||||
"optional": true
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
@ -12727,8 +12684,7 @@
|
||||||
"longest": {
|
"longest": {
|
||||||
"version": "1.0.1",
|
"version": "1.0.1",
|
||||||
"resolved": "https://registry.npmjs.org/longest/-/longest-1.0.1.tgz",
|
"resolved": "https://registry.npmjs.org/longest/-/longest-1.0.1.tgz",
|
||||||
"integrity": "sha1-MKCy2jj3N3DoKUoNIuZiXtd9AJc=",
|
"integrity": "sha1-MKCy2jj3N3DoKUoNIuZiXtd9AJc="
|
||||||
"optional": true
|
|
||||||
},
|
},
|
||||||
"lowercase-keys": {
|
"lowercase-keys": {
|
||||||
"version": "1.0.1",
|
"version": "1.0.1",
|
||||||
|
@ -13193,7 +13149,7 @@
|
||||||
"semver": "^5.5.0",
|
"semver": "^5.5.0",
|
||||||
"simple-glob": "~0.2.0",
|
"simple-glob": "~0.2.0",
|
||||||
"tar-fs": "^1.13.0",
|
"tar-fs": "^1.13.0",
|
||||||
"temp": "github:adam-lynch/node-temp#remove_tmpdir_dep",
|
"temp": "github:adam-lynch/node-temp#279c1350cb7e4f02515d91da9e35d39a40774016",
|
||||||
"thenify": "^3.3.0",
|
"thenify": "^3.3.0",
|
||||||
"update-notifier": "^2.4.0",
|
"update-notifier": "^2.4.0",
|
||||||
"winresourcer": "^0.9.0"
|
"winresourcer": "^0.9.0"
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
{
|
{
|
||||||
"name": "inav-configurator",
|
"name": "inav-configurator",
|
||||||
"description": "INAV Configurator",
|
"description": "INAV Configurator",
|
||||||
"version": "2.7.0",
|
"version": "3.0.0",
|
||||||
"main": "main.html",
|
"main": "main.html",
|
||||||
"default_locale": "en",
|
"default_locale": "en",
|
||||||
"scripts": {
|
"scripts": {
|
||||||
|
|
101
resources/models/flying_wing.json
Normal file
101
resources/models/flying_wing.json
Normal file
File diff suppressed because one or more lines are too long
BIN
resources/osd/clarity.zip
Normal file
BIN
resources/osd/clarity.zip
Normal file
Binary file not shown.
|
@ -15,8 +15,8 @@
|
||||||
z-index: 2002;
|
z-index: 2002;
|
||||||
position: absolute;
|
position: absolute;
|
||||||
width: 500px;
|
width: 500px;
|
||||||
height: 450px;
|
height: 485px;
|
||||||
overflow-y: auto;
|
overflow: none;
|
||||||
top: 0;
|
top: 0;
|
||||||
bottom: 0;
|
bottom: 0;
|
||||||
left: 0;
|
left: 0;
|
||||||
|
@ -54,4 +54,4 @@
|
||||||
|
|
||||||
.defaults_btn--not-recommended a:hover {
|
.defaults_btn--not-recommended a:hover {
|
||||||
color: #222 !important;
|
color: #222 !important;
|
||||||
}
|
}
|
||||||
|
|
|
@ -44,7 +44,9 @@ input.logic_element__operand--value {
|
||||||
.function_cell__action,
|
.function_cell__action,
|
||||||
.function_cell__operand,
|
.function_cell__operand,
|
||||||
.logic_cell__operandA,
|
.logic_cell__operandA,
|
||||||
.logic_cell__operandB {
|
.logic_cell__operandB,
|
||||||
|
.pid_cell__setpoint,
|
||||||
|
.pid_cell__measurement {
|
||||||
text-align: left;
|
text-align: left;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -117,6 +117,10 @@
|
||||||
<option value="50" i18n="adjustmentsFunction50"></option>
|
<option value="50" i18n="adjustmentsFunction50"></option>
|
||||||
<option value="51" i18n="adjustmentsFunction51"></option>
|
<option value="51" i18n="adjustmentsFunction51"></option>
|
||||||
<option value="52" i18n="adjustmentsFunction52"></option>
|
<option value="52" i18n="adjustmentsFunction52"></option>
|
||||||
|
<option value="53" i18n="adjustmentsFunction53"></option>
|
||||||
|
<option value="54" i18n="adjustmentsFunction54"></option>
|
||||||
|
<option value="55" i18n="adjustmentsFunction55"></option>
|
||||||
|
<option value="56" i18n="adjustmentsFunction56"></option>
|
||||||
</select></td>
|
</select></td>
|
||||||
<td class="adjustmentSlot"><select class="slot">
|
<td class="adjustmentSlot"><select class="slot">
|
||||||
<option value="0" i18n="adjustmentsSlot0"></option>
|
<option value="0" i18n="adjustmentsSlot0"></option>
|
||||||
|
|
|
@ -64,7 +64,7 @@ TABS.adjustments.initialize = function (callback) {
|
||||||
|
|
||||||
// update list of selected functions
|
// update list of selected functions
|
||||||
var functionListOptions = $(functionList).find('option');
|
var functionListOptions = $(functionList).find('option');
|
||||||
var availableFunctionCount = 53;
|
var availableFunctionCount = 57; // Set this to highest adjustment value + 1
|
||||||
|
|
||||||
var functionListOptions = $(functionListOptions).slice(0,availableFunctionCount);
|
var functionListOptions = $(functionListOptions).slice(0,availableFunctionCount);
|
||||||
functionList.empty().append(functionListOptions);
|
functionList.empty().append(functionListOptions);
|
||||||
|
|
|
@ -1,524 +1,453 @@
|
||||||
<div class="tab-configuration tab-advanced-tuning toolbar_fixed_bottom">
|
<div class="tab-configuration tab-advanced-tuning toolbar_fixed_bottom">
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="tab_title" data-i18n="tabAdvancedTuningTitle">Advanced tuning</div>
|
<div class="tab_title"><span data-i18n="tabAdvancedTuningTitle">Advanced Tuning</span><span class="airplaneTuningTitle">: Fixed Wing</span><span class="multirotorTuningTitle">: Multirotors</span></div>
|
||||||
|
|
||||||
<div class="leftWrapper">
|
<!-- Airplane Advanced Tuning-->
|
||||||
<div class="config-section gui_box grey">
|
<div class="airplaneTuning">
|
||||||
<div class="gui_box_titlebar">
|
<div class="leftWrapper">
|
||||||
<div class="spacer_box_title" data-i18n="multiRotorNavigationConfiguration"></div>
|
<div class="config-section gui_box grey">
|
||||||
</div>
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box">
|
<div class="spacer_box_title" data-i18n="configurationLaunch"></div>
|
||||||
<div class="select">
|
|
||||||
<select id="user-control-mode"></select>
|
|
||||||
<label for="user-control-mode"> <span data-i18n="userControlMode"></span></label>
|
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="spacer_box settings">
|
||||||
<input id="max-speed" type="number" data-simple-bind="NAV_POSHOLD.maxSpeed" step="1" min="10" max="2000">
|
<div class="number">
|
||||||
<label for="max-speed">
|
<input type="number" id="launchIdleThr" data-setting="nav_fw_launch_idle_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
<span data-i18n="posholdMaxSpeed"></span>
|
<label for="launchIdleThr"><span data-i18n="configurationLaunchIdleThr"></span></label>
|
||||||
</label>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="max-manual-speed" type="number" data-simple-bind="NAV_POSHOLD.maxManualSpeed" step="1" min="10" max="2000">
|
<input type="number" id="launchMaxAngle" data-setting="nav_fw_launch_max_angle" data-setting-multiplier="1" step="1" min="5" max="180" />
|
||||||
<label for="max-manual-speed">
|
<label for="launchMaxAngle"><span data-i18n="configurationLaunchMaxAngle"></span></label>
|
||||||
<span data-i18n="posholdMaxManualSpeed"></span>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div>
|
||||||
</label>
|
</div>
|
||||||
</div>
|
<div class="number">
|
||||||
<div class="number">
|
<input type="number" id="launchVelocity" data-setting="nav_fw_launch_velocity" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
<input id="max-climb-rate" type="number" data-simple-bind="NAV_POSHOLD.maxClimbRate" step="1" min="10" max="2000">
|
<label for="launchVelocity"><span data-i18n="configurationLaunchVelocity"></span></label>
|
||||||
<label for="max-climb-rate">
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchVelocityHelp"></div>
|
||||||
<span data-i18n="posholdMaxClimbRate"></span>
|
</div>
|
||||||
</label>
|
<div class="number">
|
||||||
</div>
|
<input type="number" id="launchAccel" data-setting="nav_fw_launch_accel" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
<div class="number">
|
<label for="launchAccel"><span data-i18n="configurationLaunchAccel"></span></label>
|
||||||
<input id="max-manual-climb-rate" type="number" data-simple-bind="NAV_POSHOLD.maxManualClimbRate" step="1" min="10" max="2000">
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchAccelHelp"></div>
|
||||||
<label for="max-manual-climb-rate">
|
</div>
|
||||||
<span data-i18n="posholdMaxManualClimbRate"></span>
|
<div class="number">
|
||||||
</label>
|
<input type="number" id="launchDetectTime" data-setting="nav_fw_launch_detect_time" data-setting-multiplier="1" step="1" min="10" max="1000" />
|
||||||
</div>
|
<label for="launchDetectTime"><span data-i18n="configurationLaunchDetectTime"></span></label>
|
||||||
<div class="number">
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchDetectTimeHelp"></div>
|
||||||
<input id="max-bank-angle" type="number" data-simple-bind="NAV_POSHOLD.maxBankAngle" step="1" min="15" max="45">
|
</div>
|
||||||
<label for="max-bank-angle">
|
<div class="number">
|
||||||
<span data-i18n="posholdMaxBankAngle"></span>
|
<input type="number" id="launchMotorDelay" data-setting="nav_fw_launch_motor_delay" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
</label>
|
<label for="launchMotorDelay"><span data-i18n="configurationLaunchMotorDelay"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="posholdMaxBankAngleHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMotorDelayHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="checkbox">
|
<div class="number">
|
||||||
<input type="checkbox" id="use-mid-throttle" class="toggle" />
|
<input type="number" id="launchMinTime" data-setting="nav_fw_launch_min_time" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
||||||
<label for="use-mid-throttle">
|
<label for="launchMinTime"><span data-i18n="configurationLaunchMinTime"></span></label>
|
||||||
<span data-i18n="posholdHoverMidThrottle"></span>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMinTimeHelp"></div>
|
||||||
</label>
|
</div>
|
||||||
</div>
|
<div class="number">
|
||||||
<div class="number">
|
<input type="number" id="launchSpinupTime" data-setting="nav_fw_launch_spinup_time" data-setting-multiplier="1" step="1" min="0" max="1000" />
|
||||||
<input id="hover-throttle" type="number" data-simple-bind="NAV_POSHOLD.hoverThrottle" step="1" min="1000" max="2000">
|
<label for="launchSpinupTime"><span data-i18n="configurationLaunchSpinupTime"></span></label>
|
||||||
<label for="hover-throttle">
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div>
|
||||||
<span data-i18n="posholdHoverThrottle"></span>
|
</div>
|
||||||
</label>
|
<div class="number">
|
||||||
</div>
|
<input type="number" id="launchThr" data-setting="nav_fw_launch_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
</div>
|
<label for="launchThr"><span data-i18n="configurationLaunchThr"></span></label>
|
||||||
</div>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div>
|
||||||
|
</div>
|
||||||
<div class="config-section gui_box grey">
|
<div class="number">
|
||||||
<div class="gui_box_titlebar">
|
<input type="number" id="launchClimbAngle" data-setting="nav_fw_launch_climb_angle" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
||||||
<div class="spacer_box_title" data-i18n="rthConfiguration"></div>
|
<label for="launchClimbAngle"><span data-i18n="configurationLaunchClimbAngle"></span></label>
|
||||||
</div>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchClimbAngleHelp"></div>
|
||||||
<div class="spacer_box">
|
</div>
|
||||||
|
<div class="number">
|
||||||
<div class="select">
|
<input type="number" id="launchTimeout" data-setting="nav_fw_launch_timeout" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
||||||
<select id="rthAltControlMode"></select>
|
<label for="launchTimeout"><span data-i18n="configurationLaunchTimeout"></span></label>
|
||||||
<label for="rthAltControlMode"> <span data-i18n="rthAltControlMode"></span></label>
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchTimeoutHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="number">
|
||||||
<div class="number">
|
<input type="number" id="launchMaxAltitude" data-setting="nav_fw_launch_max_altitude" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
||||||
<input id="rthAltitude" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.rthAltitude" step="1" min="0" max="65000">
|
<label for="launchMaxAltitude"><span data-i18n="configurationLaunchMaxAltitude"></span></label>
|
||||||
<label for="rthAltitude">
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAltitudeHelp"></div>
|
||||||
<span data-i18n="rthAltitude"></span>
|
</div>
|
||||||
</label>
|
<div class="number">
|
||||||
<div class="helpicon cf_tip" data-i18n_title="rthAltitudeHelp"></div>
|
<input type="number" id="launchEndTime" data-setting="nav_fw_launch_end_time" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
</div>
|
<label for="launchEndTime"><span data-i18n="configurationLaunchEndTime"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchEndTimeHelp"></div>
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="rthHomeAltitude" data-setting="nav_rth_home_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
|
||||||
<label for="rthHomeAltitude">
|
|
||||||
<span data-i18n="rthHomeAltitudeLabel"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="rthHomeAltitudeHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="checkbox">
|
|
||||||
<input type="checkbox" id="rth-climb-first" class="toggle" />
|
|
||||||
<label for="rth-climb-first">
|
|
||||||
<span data-i18n="rthClimbFirst"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="checkbox">
|
|
||||||
<input type="checkbox" id="rthClimbIgnoreEmergency" class="toggle" />
|
|
||||||
<label for="rthClimbIgnoreEmergency">
|
|
||||||
<span data-i18n="rthClimbIgnoreEmergency"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="checkbox">
|
|
||||||
<input type="checkbox" id="rthTailFirst" class="toggle" />
|
|
||||||
<label for="rthTailFirst">
|
|
||||||
<span data-i18n="rthTailFirst"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="select">
|
|
||||||
<select id="rthAllowLanding"></select>
|
|
||||||
<label for="rthAllowLanding">
|
|
||||||
<span data-i18n="rthAllowLanding"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="landDescentRate" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.landDescentRate" step="1" min="100" max="2000">
|
|
||||||
<label for="landDescentRate">
|
|
||||||
<span data-i18n="landDescentRate"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="landSlowdownMinAlt" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.landSlowdownMinAlt" step="1" min="50" max="1000">
|
|
||||||
<label for="landSlowdownMinAlt">
|
|
||||||
<span data-i18n="landSlowdownMinAlt"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="landSlowdownMaxAlt" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.landSlowdownMaxAlt" step="1" min="500" max="4000">
|
|
||||||
<label for="landSlowdownMaxAlt">
|
|
||||||
<span data-i18n="landSlowdownMaxAlt"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="rth-min-distance" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.minRthDistance" step="1" min="0" max="5000">
|
|
||||||
<label for="rth-min-distance">
|
|
||||||
<span data-i18n="minRthDistance"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="minRthDistanceHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="rthAbortThreshold" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.rthAbortThreshold" step="1" min="0" max="65000">
|
|
||||||
<label for="rthAbortThreshold">
|
|
||||||
<span data-i18n="rthAbortThreshold"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="rthAbortThresholdHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="emergencyDescentRate" type="number" data-simple-bind="RTH_AND_LAND_CONFIG.emergencyDescentRate" step="1" min="10" max="2000">
|
|
||||||
<label for="emergencyDescentRate">
|
|
||||||
<span data-i18n="emergencyDescentRate"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="config-section gui_box grey">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="configurationLaunch"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box settings">
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchIdleThr" data-setting="nav_fw_launch_idle_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
|
||||||
<label for="launchIdleThr">
|
|
||||||
<span data-i18n="configurationLaunchIdleThr"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchMaxAngle" data-setting="nav_fw_launch_max_angle" data-setting-multiplier="1" step="1" min="5" max="180" />
|
|
||||||
<label for="launchMaxAngle">
|
|
||||||
<span data-i18n="configurationLaunchMaxAngle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchVelocity" data-setting="nav_fw_launch_velocity" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
|
||||||
<label for="launchVelocity">
|
|
||||||
<span data-i18n="configurationLaunchVelocity"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchVelocityHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchAccel" data-setting="nav_fw_launch_accel" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
|
||||||
<label for="launchAccel">
|
|
||||||
<span data-i18n="configurationLaunchAccel"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchAccelHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchDetectTime" data-setting="nav_fw_launch_detect_time" data-setting-multiplier="1" step="1" min="10" max="1000" />
|
|
||||||
<label for="launchDetectTime">
|
|
||||||
<span data-i18n="configurationLaunchDetectTime"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchDetectTimeHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchMotorDelay" data-setting="nav_fw_launch_motor_delay" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
|
||||||
<label for="launchMotorDelay">
|
|
||||||
<span data-i18n="configurationLaunchMotorDelay"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMotorDelayHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchMinTime" data-setting="nav_fw_launch_min_time" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
|
||||||
<label for="launchMinTime">
|
|
||||||
<span data-i18n="configurationLaunchMinTime"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMinTimeHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchSpinupTime" data-setting="nav_fw_launch_spinup_time" data-setting-multiplier="1" step="1" min="0" max="1000" />
|
|
||||||
<label for="launchSpinupTime">
|
|
||||||
<span data-i18n="configurationLaunchSpinupTime"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchThr" data-setting="nav_fw_launch_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
|
||||||
<label for="launchThr">
|
|
||||||
<span data-i18n="configurationLaunchThr"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchClimbAngle" data-setting="nav_fw_launch_climb_angle" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
|
||||||
<label for="launchClimbAngle">
|
|
||||||
<span data-i18n="configurationLaunchClimbAngle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchClimbAngleHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchTimeout" data-setting="nav_fw_launch_timeout" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
|
||||||
<label for="launchTimeout">
|
|
||||||
<span data-i18n="configurationLaunchTimeout"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchTimeoutHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchMaxAltitude" data-setting="nav_fw_launch_max_altitude" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
|
||||||
<label for="launchMaxAltitude">
|
|
||||||
<span data-i18n="configurationLaunchMaxAltitude"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAltitudeHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchEndTime" data-setting="nav_fw_launch_end_time" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
|
||||||
<label for="launchEndTime">
|
|
||||||
<span data-i18n="configurationLaunchEndTime"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationLaunchEndTimeHelp"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="rightWrapper">
|
|
||||||
|
|
||||||
<div class="config-section gui_box grey">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="positionEstimatorConfiguration"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="note spacebottom">
|
|
||||||
<div class="note_spacer" >
|
|
||||||
<p data-i18n="positionEstimatorConfigurationDisclaimer"></p>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
</div>
|
||||||
<input id="w_z_baro_p" type="number" data-simple-bind="POSITION_ESTIMATOR.w_z_baro_p" step="0.01" min="0" max="10">
|
|
||||||
<label for="w_z_baro_p">
|
<div class="config-section gui_box grey">
|
||||||
<span data-i18n="w_z_baro_p"></span>
|
<div class="gui_box_titlebar">
|
||||||
</label>
|
<div class="spacer_box_title" data-i18n="powerConfiguration"></div>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="w_z_baro_p_help"></div>
|
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="spacer_box">
|
||||||
<input id="w_z_gps_p" type="number" data-simple-bind="POSITION_ESTIMATOR.w_z_gps_p" step="0.01" min="0" max="10">
|
<div class="number">
|
||||||
<label for="w_z_gps_p">
|
<input type="number" id="idlePower" data-setting="idle_power" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
<span data-i18n="w_z_gps_p"></span>
|
<label for="idlePower"><span data-i18n="idlePower"></span></label>
|
||||||
</label>
|
<div class="helpicon cf_tip" data-i18n_title="idlePowerHelp"></div>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="w_z_gos_p_help"></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="5000" />
|
||||||
<input id="w_z_gps_v" type="number" data-simple-bind="POSITION_ESTIMATOR.w_z_gps_v" step="0.01" min="0" max="10">
|
<label for="cruisePower"><span data-i18n="cruisePower"></span></label>
|
||||||
<label for="w_z_gps_v">
|
<div class="helpicon cf_tip" data-i18n_title="cruisePowerHelp"></div>
|
||||||
<span data-i18n="w_z_gps_v"></span>
|
</div>
|
||||||
</label>
|
<div class="number">
|
||||||
</div>
|
<input type="number" id="cruiseSpeed" data-setting="nav_fw_cruise_speed" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
<div class="number">
|
<label for="cruiseSpeed"><span data-i18n="cruiseSpeed"></span></label>
|
||||||
<input id="w_xy_gps_p" type="number" data-simple-bind="POSITION_ESTIMATOR.w_xy_gps_p" step="0.01" min="0" max="10">
|
<div class="helpicon cf_tip" data-i18n_title="cruiseSpeedHelp"></div>
|
||||||
<label for="w_xy_gps_p">
|
</div>
|
||||||
<span data-i18n="w_xy_gps_p"></span>
|
<div class="number">
|
||||||
</label>
|
<input type="number" id="rthEnergyMargin" data-setting="rth_energy_margin" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
</div>
|
<label for="rthEnergyMargin"><span data-i18n="rthEnergyMargin"></span></label>
|
||||||
<div class="number">
|
<div class="helpicon cf_tip" data-i18n_title="rthEnergyMarginHelp"></div>
|
||||||
<input id="w_xy_gps_v" type="number" data-simple-bind="POSITION_ESTIMATOR.w_xy_gps_v" step="0.01" min="0" max="10">
|
</div>
|
||||||
<label for="w_xy_gps_v">
|
|
||||||
<span data-i18n="w_xy_gps_v"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input id="gps_min_sats" type="number" data-simple-bind="POSITION_ESTIMATOR.gps_min_sats" step="1" min="5" max="10">
|
|
||||||
<label for="gps_min_sats">
|
|
||||||
<span data-i18n="gps_min_sats"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="config-section gui_box grey">
|
</div> <!-- left wrapper -->
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="fixedWingNavigationConfiguration"></div>
|
<div class="rightWrapper">
|
||||||
|
<div class="config-section gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="fixedWingNavigationConfiguration"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="cruiseThrottle" type="number" data-setting="nav_fw_cruise_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
|
<label for="cruiseThrottle"><span data-i18n="cruiseThrottle"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="pitchToThrottle" type="number" data-setting="nav_fw_pitch2thr" data-setting-multiplier="1" step="1" min="0" max="100" />
|
||||||
|
<label for="pitchToThrottle"><span data-i18n="pitchToThrottle"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" id="cruiseManualThrottle" data-setting="nav_fw_allow_manual_thr_increase" data-live="true" />
|
||||||
|
<label for="cruiseManualThrottle"><span data-i18n="cruiseManualThrottleLabel"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="cruiseManualThrottleHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="minThrottle" type="number" data-setting="nav_fw_min_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
|
<label for="minThrottle"><span data-i18n="minThrottle"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="maxThrottle" type="number" data-setting="nav_fw_max_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
|
<label for="maxThrottle"><span data-i18n="maxThrottle"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="pitchToThrottleSmoothing" type="number" data-setting="nav_fw_pitch2thr_smoothing" data-setting-multiplier="1" step="0" min="0" max="9" />
|
||||||
|
<label for="pitchToThrottleSmoothing"><span data-i18n="pitchToThrottleSmoothing"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleSmoothingHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="pitchToThrottleThreshold" type="number" data-setting="nav_fw_pitch2thr_threshold" data-setting-multiplier="1" step="1" min="0" max="900" />
|
||||||
|
<label for="pitchToThrottleThreshold"><span data-i18n="pitchToThrottleThreshold"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleThresholdHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="cruiseYawRate" data-setting="nav_fw_cruise_yaw_rate" data-setting-multiplier="1" step="1" min="0" max="60" />
|
||||||
|
<label for="cruiseYawRate"><span data-i18n="cruiseYawRateLabel"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="cruiseYawRateHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="maxBankAngle" type="number" data-setting="nav_fw_bank_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
|
||||||
|
<label for="maxBankAngle"><span data-i18n="maxBankAngle"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="maxBankAngleHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="maxClimbAngle" type="number" data-setting="nav_fw_climb_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
|
||||||
|
<label for="maxClimbAngle"><span data-i18n="maxClimbAngle"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="maxClimbAngleHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="maxDiveAngle" type="number" data-setting="nav_fw_dive_angle" data-setting-multiplier="1" step="1" min="5" max="80" />
|
||||||
|
<label for="maxDiveAngle"><span data-i18n="maxDiveAngle"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="maxDiveAngleHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="loiterRadius" type="number" data-setting="nav_fw_loiter_radius" data-setting-multiplier="1" step="1" min="0" max="30000" />
|
||||||
|
<label for="loiterRadius"><span data-i18n="loiterRadius"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="select">
|
||||||
|
<select id="loiterDirection" data-setting="fw_loiter_direction"></select>
|
||||||
|
<label for="loiterDirection"><span data-i18n="loiterDirectionLabel"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="loiterDirectionHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="controlSmoothness" data-setting="nav_fw_control_smoothness" data-setting-multiplier="1" step="1" min="0" max="9" />
|
||||||
|
<label for="controlSmoothness"><span data-i18n="controlSmoothness"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="controlSmoothnessHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
|
||||||
|
|
||||||
<div class="number">
|
</div> <!-- right wrapper -->
|
||||||
<input id="cruiseThrottle" type="number" data-simple-bind="FW_CONFIG.cruiseThrottle" step="1" min="1000" max="2000">
|
|
||||||
<label for="cruiseThrottle">
|
<div class="clear-both"></div>
|
||||||
<span data-i18n="cruiseThrottle"></span>
|
</div> <!-- Airplane Advanced Tuning -->
|
||||||
</label>
|
|
||||||
|
<!-- Multirotor Advanced tuning -->
|
||||||
|
<div class="multirotorTuning">
|
||||||
|
<div class="leftWrapper">
|
||||||
|
<div class="config-section gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="multiRotorNavigationConfiguration"></div>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
<div class="number">
|
<div class="select">
|
||||||
<input type="number" id="cruiseYawRate" data-setting="nav_fw_cruise_yaw_rate" data-setting-multiplier="1" step="1" min="0" max="60" />
|
<select id="user-control-mode" data-setting="nav_user_control_mode"></select>
|
||||||
<label for="cruiseYawRate">
|
<label for="user-control-mode"><span data-i18n="userControlMode"></span></label>
|
||||||
<span data-i18n="cruiseYawRateLabel"></span>
|
</div>
|
||||||
</label>
|
<div class="number">
|
||||||
<div class="helpicon cf_tip" data-i18n_title="cruiseYawRateHelp"></div>
|
<input id="max-speed" type="number" data-setting="nav_auto_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
|
<label for="max-speed"><span data-i18n="posholdMaxSpeed"></span></label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input id="max-manual-speed" type="number" data-setting="nav_manual_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
|
<label for="max-manual-speed"><span data-i18n="posholdMaxManualSpeed"></span></label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input id="max-bank-angle" type="number" data-setting="nav_mc_bank_angle" data-setting-multiplier="1" step="1" min="15" max="45" />
|
||||||
|
<label for="max-bank-angle"><span data-i18n="posholdMaxBankAngle"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="posholdMaxBankAngleHelp"></div>
|
||||||
|
</div>
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" id="use-mid-throttle" data-setting="nav_use_midthr_for_althold" data-live="true" />
|
||||||
|
<label for="use-mid-throttle"><span data-i18n="posholdHoverMidThrottle"></span></label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input id="hover-throttle" type="number" data-setting="nav_mc_hover_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
|
<label for="hover-throttle"><span data-i18n="posholdHoverThrottle"></span></label>
|
||||||
|
</div>
|
||||||
|
<div class="checkbox">
|
||||||
|
<input id="wp-slowdown" type="checkbox" class="toggle update_preview" data-setting="nav_mc_wp_slowdown" data-live="true" />
|
||||||
|
<label for="wp-slowdown"><span data-i18n="mcWpSlowdown"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="mcWpSlowdownHelp"></div>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="select">
|
|
||||||
<select id="cruiseManualThrottle" data-setting="nav_fw_allow_manual_thr_increase"></select>
|
|
||||||
<label for="cruiseManualThrottle">
|
|
||||||
<span data-i18n="cruiseManualThrottleLabel"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="cruiseManualThrottleHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="minThrottle" type="number" data-simple-bind="FW_CONFIG.minThrottle" step="1" min="1000" max="2000">
|
|
||||||
<label for="minThrottle">
|
|
||||||
<span data-i18n="minThrottle"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="maxThrottle" type="number" data-simple-bind="FW_CONFIG.maxThrottle" step="1" min="1000" max="2000">
|
|
||||||
<label for="maxThrottle">
|
|
||||||
<span data-i18n="maxThrottle"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="maxBankAngle" type="number" data-simple-bind="FW_CONFIG.maxBankAngle" step="1" min="5" max="80">
|
|
||||||
<label for="maxBankAngle">
|
|
||||||
<span data-i18n="maxBankAngle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="maxBankAngleHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="maxClimbAngle" type="number" data-simple-bind="FW_CONFIG.maxClimbAngle" step="1" min="5" max="80">
|
|
||||||
<label for="maxClimbAngle">
|
|
||||||
<span data-i18n="maxClimbAngle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="maxClimbAngleHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="maxDiveAngle" type="number" data-simple-bind="FW_CONFIG.maxDiveAngle" step="1" min="5" max="80">
|
|
||||||
<label for="maxDiveAngle">
|
|
||||||
<span data-i18n="maxDiveAngle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="maxDiveAngleHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="pitchToThrottle" type="number" data-simple-bind="FW_CONFIG.pitchToThrottle" step="1" min="0" max="100">
|
|
||||||
<label for="pitchToThrottle">
|
|
||||||
<span data-i18n="pitchToThrottle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="loiterRadius" type="number" data-simple-bind="FW_CONFIG.loiterRadius" step="1" min="0" max="10000">
|
|
||||||
<label for="loiterRadius">
|
|
||||||
<span data-i18n="loiterRadius"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="select">
|
|
||||||
<select id="loiterDirection" data-setting="fw_loiter_direction"></select>
|
|
||||||
<label for="loiterDirection">
|
|
||||||
<span data-i18n="loiterDirectionLabel"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="loiterDirectionHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="controlSmoothness" data-setting="nav_fw_control_smoothness" data-setting-multiplier="1" step="1" min="0" max="9" />
|
|
||||||
<label for="controlSmoothness">
|
|
||||||
<span data-i18n="controlSmoothness"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="controlSmoothnessHelp"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div> <!-- left wrapper -->
|
||||||
|
|
||||||
<div class="config-section gui_box grey">
|
<div class="rightWrapper">
|
||||||
<div class="gui_box_titlebar">
|
<div class="config-section gui_box grey">
|
||||||
<div class="spacer_box_title" data-i18n="waypointConfiguration"></div>
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="multirotorBrakingConfiguration"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingSpeedThreshold" type="number" data-setting="nav_mc_braking_speed_threshold" data-setting-multiplier="1" step="1" min="0" max="1000" />
|
||||||
|
<label for="brakingSpeedThreshold"><span data-i18n="brakingSpeedThreshold"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingSpeedThresholdTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingDisengageSpeed" type="number" data-setting="nav_mc_braking_disengage_speed" data-setting-multiplier="1" step="1" min="0" max="1000" />
|
||||||
|
<label for="brakingDisengageSpeed"><span data-i18n="brakingDisengageSpeed"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingDisengageSpeedTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingTimeout" type="number" data-setting="nav_mc_braking_timeout" data-setting-multiplier="1" step="1" min="100" max="5000" />
|
||||||
|
<label for="brakingTimeout"><span data-i18n="brakingTimeout"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingTimeoutTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingBoostFactor" type="number" data-setting="nav_mc_braking_boost_factor" data-setting-multiplier="1" step="1" min="0" max="200" />
|
||||||
|
<label for="brakingBoostFactor"><span data-i18n="brakingBoostFactor"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingBoostFactorTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingBoostTimeout" type="number" data-setting="nav_mc_braking_boost_timeout" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
|
<label for="brakingBoostTimeout"><span data-i18n="brakingBoostTimeout"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingBoostTimeoutTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingBoostSpeedThreshold" type="number" data-setting="nav_mc_braking_boost_speed_threshold" data-setting-multiplier="1" step="1" min="100" max="1000" />
|
||||||
|
<label for="brakingBoostSpeedThreshold"><span data-i18n="brakingBoostSpeedThreshold"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingBoostSpeedThresholdTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingBoostDisengageSpeed" type="number" data-setting="nav_mc_braking_boost_disengage_speed" data-setting-multiplier="1" step="1" min="100" max="1000" />
|
||||||
|
<label for="brakingBoostDisengageSpeed"><span data-i18n="brakingBoostDisengageSpeed"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingBoostDisengageSpeedTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="brakingBankAngle" type="number" data-setting="nav_mc_braking_bank_angle" data-setting-multiplier="1" step="1" min="15" max="60" />
|
||||||
|
<label for="brakingBankAngle"><span data-i18n="brakingBankAngle"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="brakingBankAngleTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
</div> <!-- right wrapper -->
|
||||||
|
|
||||||
<div class="number">
|
<div class="clear-both"></div>
|
||||||
<input type="number" id="waypointRadius" data-setting="nav_wp_radius" data-setting-multiplier="1" step="1" min="10" max="10000" />
|
</div> <!-- Multirotor Advanced Tuning -->
|
||||||
<label for="waypointRadius">
|
|
||||||
<span data-i18n="waypointRadius"></span>
|
<!-- Common tuning -->
|
||||||
</label>
|
<div class="tab_subtitle" data-i18n="tabAdvancedTuningGenericTitle">Advanced Tuning: Generic settings</div>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="waypointRadiusHelp"></div>
|
<div>
|
||||||
|
<div class="leftWrapper">
|
||||||
|
|
||||||
|
<div class="config-section gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="rthConfiguration"></div>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
|
||||||
|
<div class="select">
|
||||||
|
<select id="rthAltControlMode" data-setting="nav_rth_alt_mode"></select>
|
||||||
|
<label for="rthAltControlMode"><span data-i18n="rthAltControlMode"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="rthAltitude" data-setting="nav_rth_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
|
<label for="rthAltitude"><span data-i18n="rthAltitude"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="rthAltitudeHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="rthHomeAltitude" data-setting="nav_rth_home_altitude" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
|
<label for="rthHomeAltitude"><span data-i18n="rthHomeAltitudeLabel"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="rthHomeAltitudeHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="select">
|
||||||
|
<select id="rth-climb-first" data-setting="nav_rth_climb_first"></select>
|
||||||
|
<label for="rth-climb-first"><span data-i18n="rthClimbFirst"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="rthClimbFirstHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" id="rthClimbIgnoreEmergency" data-setting="nav_rth_climb_ignore_emerg" data-live="true" />
|
||||||
|
<label for="rthClimbIgnoreEmergency"><span data-i18n="rthClimbIgnoreEmergency"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="checkbox">
|
||||||
<input type="number" id="waypointSafeDistance" data-setting="nav_wp_safe_distance" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
<input type="checkbox" class="toggle update_preview" id="rthAltControlOverride" data-setting="nav_rth_alt_control_override" data-live="true" />
|
||||||
<label for="waypointSafeDistance">
|
<label for="rthAltControlOverride"><span data-i18n="rthAltControlOverride"></span></label>
|
||||||
<span data-i18n="waypointSafeDistance"></span>
|
<div class="helpicon cf_tip" data-i18n_title="rthAltControlOverrideHelp"></div>
|
||||||
</label>
|
</div>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="waypointSafeDistanceHelp"></div>
|
|
||||||
|
<div class="checkbox notFixedWingTuning">
|
||||||
|
<input type="checkbox" class="toggle update_preview" id="rthTailFirst" data-setting="nav_rth_tail_first" data-live="true" />
|
||||||
|
<label for="rthTailFirst"><span data-i18n="rthTailFirst"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="select">
|
||||||
|
<select id="rthAllowLanding" data-setting="nav_rth_allow_landing"></select>
|
||||||
|
<label for="rthAllowLanding"><span data-i18n="rthAllowLanding"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="landDescentRate" type="number" data-setting="nav_landing_speed" data-setting-multiplier="1" step="1" min="100" max="2000" />
|
||||||
|
<label for="landDescentRate"><span data-i18n="landDescentRate"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="landSlowdownMinAlt" type="number" data-setting="nav_land_slowdown_minalt" data-setting-multiplier="1" step="1" min="50" max="1000" />
|
||||||
|
<label for="landSlowdownMinAlt"><span data-i18n="landSlowdownMinAlt"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="landSlowdownMaxAlt" type="number" data-setting="nav_land_slowdown_maxalt" data-setting-multiplier="1" step="1" min="500" max="4000" />
|
||||||
|
<label for="landSlowdownMaxAlt"><span data-i18n="landSlowdownMaxAlt"></span></label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="rth-min-distance" type="number" data-setting="nav_min_rth_distance" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
|
<label for="rth-min-distance"><span data-i18n="minRthDistance"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="minRthDistanceHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="rthAbortThreshold" type="number" data-setting="nav_rth_abort_threshold" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
|
<label for="rthAbortThreshold"><span data-i18n="rthAbortThreshold"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="rthAbortThresholdHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input id="emergencyDescentRate" type="number" data-setting="nav_emerg_landing_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
|
<label for="emergencyDescentRate"><span data-i18n="emergencyDescentRate"></span></label>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
|
</div> <!-- Left wrapper -->
|
||||||
|
|
||||||
<div class="config-section gui_box grey">
|
<div class="rightWrapper">
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="multirotorBrakingConfiguration"></div>
|
<div class="config-setion gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="generalNavigationSettings"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="navManualClimbRate" data-setting="nav_manual_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
|
<label for="navManualClimbRate"><span data-i18n="navManualClimbRate"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="navManualClimbRateHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="navAutoClimbRate" data-setting="nav_auto_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
|
<label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
|
||||||
|
|
||||||
<div class="number">
|
<div class="config-section gui_box grey">
|
||||||
<input id="brakingSpeedThreshold" type="number" data-simple-bind="BRAKING_CONFIG.speedThreshold" step="1" min="0" max="1000">
|
<div class="gui_box_titlebar">
|
||||||
<label for="brakingSpeedThreshold">
|
<div class="spacer_box_title" data-i18n="waypointConfiguration"></div>
|
||||||
<span data-i18n="brakingSpeedThreshold"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingSpeedThresholdTip"></div>
|
|
||||||
</div>
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
<div class="number">
|
|
||||||
<input id="brakingDisengageSpeed" type="number" data-simple-bind="BRAKING_CONFIG.disengageSpeed" step="1" min="0" max="1000">
|
<div class="number">
|
||||||
<label for="brakingDisengageSpeed">
|
<input type="number" id="waypointRadius" data-setting="nav_wp_radius" data-setting-multiplier="1" step="1" min="10" max="10000" />
|
||||||
<span data-i18n="brakingDisengageSpeed"></span>
|
<label for="waypointRadius"><span data-i18n="waypointRadius"></span></label>
|
||||||
</label>
|
<div class="helpicon cf_tip" data-i18n_title="waypointRadiusHelp"></div>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingDisengageSpeedTip"></div>
|
</div>
|
||||||
|
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="waypointSafeDistance" data-setting="nav_wp_safe_distance" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
|
<label for="waypointSafeDistance"><span data-i18n="waypointSafeDistance"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="waypointSafeDistanceHelp"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="brakingTimeout" type="number" data-simple-bind="BRAKING_CONFIG.timeout" step="1" min="100" max="5000">
|
|
||||||
<label for="brakingTimeout">
|
|
||||||
<span data-i18n="brakingTimeout"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingTimeoutTip"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="brakingBoostFactor" type="number" data-simple-bind="BRAKING_CONFIG.boostFactor" step="1" min="0" max="200">
|
|
||||||
<label for="brakingBoostFactor">
|
|
||||||
<span data-i18n="brakingBoostFactor"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingBoostFactorTip"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="brakingBoostTimeout" type="number" data-simple-bind="BRAKING_CONFIG.boostTimeout" step="1" min="0" max="5000">
|
|
||||||
<label for="brakingBoostTimeout">
|
|
||||||
<span data-i18n="brakingBoostTimeout"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingBoostTimeoutTip"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="brakingBoostSpeedThreshold" type="number" data-simple-bind="BRAKING_CONFIG.boostSpeedThreshold" step="1" min="100" max="1000">
|
|
||||||
<label for="brakingBoostSpeedThreshold">
|
|
||||||
<span data-i18n="brakingBoostSpeedThreshold"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingBoostSpeedThresholdTip"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="brakingBoostDisengageSpeed" type="number" data-simple-bind="BRAKING_CONFIG.boostDisengageSpeed" step="1" min="100" max="1000">
|
|
||||||
<label for="brakingBoostDisengageSpeed">
|
|
||||||
<span data-i18n="brakingBoostDisengageSpeed"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingBoostDisengageSpeedTip"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="number">
|
|
||||||
<input id="brakingBankAngle" type="number" data-simple-bind="BRAKING_CONFIG.bankAngle" step="1" min="15" max="60">
|
|
||||||
<label for="brakingBankAngle">
|
|
||||||
<span data-i18n="brakingBankAngle"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="brakingBankAngleTip"></div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
</div> <!-- Right wrapper -->
|
||||||
|
|
||||||
|
</div> <!-- Common tuning -->
|
||||||
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
<div class="content_toolbar">
|
<div class="content_toolbar">
|
||||||
<div class="btn save_btn">
|
<div class="btn save_btn">
|
||||||
<a id="advanced-tuning-save-button" class="save" href="#" data-i18n="advancedTuningSave"></a>
|
<a id="advanced-tuning-save-button" class="save" href="#" data-i18n="advancedTuningSave"></a>
|
||||||
|
|
|
@ -4,109 +4,39 @@ TABS.advanced_tuning = {};
|
||||||
|
|
||||||
TABS.advanced_tuning.initialize = function (callback) {
|
TABS.advanced_tuning.initialize = function (callback) {
|
||||||
|
|
||||||
var loadChainer = new MSPChainerClass(),
|
|
||||||
saveChainer = new MSPChainerClass();
|
|
||||||
|
|
||||||
if (GUI.active_tab != 'advanced_tuning') {
|
if (GUI.active_tab != 'advanced_tuning') {
|
||||||
GUI.active_tab = 'advanced_tuning';
|
GUI.active_tab = 'advanced_tuning';
|
||||||
googleAnalytics.sendAppView('AdvancedTuning');
|
googleAnalytics.sendAppView('AdvancedTuning');
|
||||||
}
|
}
|
||||||
|
|
||||||
loadChainer.setChain([
|
loadHtml();
|
||||||
mspHelper.loadNavPosholdConfig,
|
|
||||||
mspHelper.loadPositionEstimationConfig,
|
|
||||||
mspHelper.loadRthAndLandConfig,
|
|
||||||
mspHelper.loadFwConfig,
|
|
||||||
mspHelper.loadBrakingConfig
|
|
||||||
]);
|
|
||||||
loadChainer.setExitPoint(loadHtml);
|
|
||||||
loadChainer.execute();
|
|
||||||
|
|
||||||
saveChainer.setChain([
|
|
||||||
mspHelper.saveNavPosholdConfig,
|
|
||||||
mspHelper.savePositionEstimationConfig,
|
|
||||||
mspHelper.saveRthAndLandConfig,
|
|
||||||
mspHelper.saveFwConfig,
|
|
||||||
mspHelper.saveBrakingConfig,
|
|
||||||
mspHelper.saveToEeprom
|
|
||||||
]);
|
|
||||||
saveChainer.setExitPoint(reboot);
|
|
||||||
|
|
||||||
function loadHtml() {
|
function loadHtml() {
|
||||||
GUI.load("./tabs/advanced_tuning.html", Settings.processHtml(function () {
|
GUI.load("./tabs/advanced_tuning.html", Settings.processHtml(function () {
|
||||||
|
|
||||||
var $userControlMode = $('#user-control-mode'),
|
if (FC.isAirplane()) {
|
||||||
$useMidThrottle = $("#use-mid-throttle"),
|
$('.airplaneTuning').show();
|
||||||
$rthClimbFirst = $('#rth-climb-first'),
|
$('.airplaneTuningTitle').show();
|
||||||
$rthClimbIgnoreEmergency = $('#rthClimbIgnoreEmergency'),
|
$('.multirotorTuning').hide();
|
||||||
$rthTailFirst = $('#rthTailFirst'),
|
$('.multirotorTuningTitle').hide();
|
||||||
$rthAllowLanding = $('#rthAllowLanding'),
|
$('.notFixedWingTuning').hide();
|
||||||
$rthAltControlMode = $('#rthAltControlMode');
|
} else if (FC.isMultirotor()) {
|
||||||
|
$('.airplaneTuning').hide();
|
||||||
$rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst);
|
$('.airplaneTuningTitle').hide();
|
||||||
$rthClimbFirst.change(function () {
|
$('.multirotorTuning').show();
|
||||||
if ($(this).is(":checked")) {
|
$('.multirotorTuningTitle').show();
|
||||||
RTH_AND_LAND_CONFIG.rthClimbFirst = 1;
|
$('.notFixedWingTuning').show();
|
||||||
} else {
|
} else {
|
||||||
RTH_AND_LAND_CONFIG.rthClimbFirst = 0;
|
$('.airplaneTuning').show();
|
||||||
}
|
$('.airplaneTuningTitle').hide();
|
||||||
});
|
$('.multirotorTuning').show();
|
||||||
$rthClimbFirst.change();
|
$('.multirotorTuningTitle').hide();
|
||||||
|
$('.notFixedWingTuning').show();
|
||||||
$rthClimbIgnoreEmergency.prop("checked", RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency);
|
}
|
||||||
$rthClimbIgnoreEmergency.change(function () {
|
|
||||||
if ($(this).is(":checked")) {
|
|
||||||
RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency = 1;
|
|
||||||
} else {
|
|
||||||
RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency = 0;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
$rthClimbIgnoreEmergency.change();
|
|
||||||
|
|
||||||
$rthTailFirst.prop("checked", RTH_AND_LAND_CONFIG.rthTailFirst);
|
|
||||||
$rthTailFirst.change(function () {
|
|
||||||
if ($(this).is(":checked")) {
|
|
||||||
RTH_AND_LAND_CONFIG.rthTailFirst = 1;
|
|
||||||
} else {
|
|
||||||
RTH_AND_LAND_CONFIG.rthTailFirst = 0;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
$rthTailFirst.change();
|
|
||||||
|
|
||||||
GUI.fillSelect($rthAltControlMode, FC.getRthAltControlMode(), RTH_AND_LAND_CONFIG.rthAltControlMode);
|
|
||||||
$rthAltControlMode.val(RTH_AND_LAND_CONFIG.rthAltControlMode);
|
|
||||||
$rthAltControlMode.change(function () {
|
|
||||||
RTH_AND_LAND_CONFIG.rthAltControlMode = $rthAltControlMode.val();
|
|
||||||
});
|
|
||||||
GUI.fillSelect($rthAllowLanding, FC.getRthAllowLanding(), RTH_AND_LAND_CONFIG.rthAllowLanding);
|
|
||||||
$rthAllowLanding.val(RTH_AND_LAND_CONFIG.rthAllowLanding);
|
|
||||||
$rthAllowLanding.change(function () {
|
|
||||||
RTH_AND_LAND_CONFIG.rthAllowLanding = $rthAllowLanding.val();
|
|
||||||
});
|
|
||||||
|
|
||||||
GUI.fillSelect($userControlMode, FC.getUserControlMode(), NAV_POSHOLD.userControlMode);
|
|
||||||
$userControlMode.val(NAV_POSHOLD.userControlMode);
|
|
||||||
$userControlMode.change(function () {
|
|
||||||
NAV_POSHOLD.userControlMode = $userControlMode.val();
|
|
||||||
});
|
|
||||||
|
|
||||||
$useMidThrottle.prop("checked", NAV_POSHOLD.useThrottleMidForAlthold);
|
|
||||||
$useMidThrottle.change(function () {
|
|
||||||
if ($(this).is(":checked")) {
|
|
||||||
NAV_POSHOLD.useThrottleMidForAlthold = 1;
|
|
||||||
} else {
|
|
||||||
NAV_POSHOLD.useThrottleMidForAlthold = 0;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
$useMidThrottle.change();
|
|
||||||
|
|
||||||
GUI.simpleBind();
|
GUI.simpleBind();
|
||||||
|
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
$('#advanced-tuning-save-button').click(function () {
|
|
||||||
saveChainer.execute();
|
|
||||||
});
|
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
Settings.saveInputs().then(function () {
|
Settings.saveInputs().then(function () {
|
||||||
|
@ -117,6 +47,7 @@ TABS.advanced_tuning.initialize = function (callback) {
|
||||||
setTimeout(function () {
|
setTimeout(function () {
|
||||||
$(self).html(oldText);
|
$(self).html(oldText);
|
||||||
}, 2000);
|
}, 2000);
|
||||||
|
reboot();
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
|
|
|
@ -28,8 +28,68 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
|
sort_modes_for_display();
|
||||||
GUI.load("./tabs/auxiliary.html", process_html);
|
GUI.load("./tabs/auxiliary.html", process_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function sort_modes_for_display() {
|
||||||
|
// This array defines the order that the modes are displayed in the configurator modes page
|
||||||
|
configuratorBoxOrder = [
|
||||||
|
"ARM", "PREARM", // Arming
|
||||||
|
"ANGLE", "HORIZON", "MANUAL", // Flight modes
|
||||||
|
"NAV RTH", "NAV POSHOLD", "NAV COURSE HOLD", // Navigation mode
|
||||||
|
"NAV ALTHOLD", "HEADING HOLD", "AIR MODE", // Flight mode modifiers
|
||||||
|
"NAV WP", "GCS NAV", "HOME RESET", // Navigation
|
||||||
|
"SERVO AUTOTRIM", "AUTO TUNE", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON", // Fixed wing specific
|
||||||
|
"TURTLE", "FPV ANGLE MIX", "TURN ASSIST", "MC BRAKING", "SURFACE", "HEADFREE", "HEADADJ", // Multi-rotor specific
|
||||||
|
"BEEPER", "LEDS OFF", "LIGHTS", // Feedback
|
||||||
|
"OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3", // OSD
|
||||||
|
"CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3", // FPV Camera
|
||||||
|
"BLACKBOX", "FAILSAFE", "KILLSWITCH", "TELEMETRY", "MSP RC OVERRIDE", "USER1", "USER2" // Misc
|
||||||
|
];
|
||||||
|
|
||||||
|
// Sort the modes
|
||||||
|
var tmpAUX_CONFIG = [];
|
||||||
|
var tmpAUX_CONFIG_IDS =[];
|
||||||
|
var found = false;
|
||||||
|
var sortedID = 0;
|
||||||
|
|
||||||
|
for (i=0; i<AUX_CONFIG.length; i++) {
|
||||||
|
tmpAUX_CONFIG[i] = AUX_CONFIG[i];
|
||||||
|
tmpAUX_CONFIG_IDS[i] = AUX_CONFIG_IDS[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
AUX_CONFIG = [];
|
||||||
|
AUX_CONFIG_IDS = [];
|
||||||
|
|
||||||
|
for (i=0; i<configuratorBoxOrder.length; i++) {
|
||||||
|
for(j=0; j<tmpAUX_CONFIG.length; j++) {
|
||||||
|
if (configuratorBoxOrder[i] === tmpAUX_CONFIG[j]) {
|
||||||
|
AUX_CONFIG[sortedID] = tmpAUX_CONFIG[j];
|
||||||
|
AUX_CONFIG_IDS[sortedID++] = tmpAUX_CONFIG_IDS[j];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// There are modes that are missing from the configuratorBoxOrder array. Add them to the end until they are ordered correctly.
|
||||||
|
if (tmpAUX_CONFIG.length > AUX_CONFIG.length) {
|
||||||
|
for (i=0; i<tmpAUX_CONFIG.length; i++) {
|
||||||
|
found = false;
|
||||||
|
for (j=0; j<AUX_CONFIG.length; j++) {
|
||||||
|
if (tmpAUX_CONFIG[i] === AUX_CONFIG[j]) {
|
||||||
|
found = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!found) {
|
||||||
|
AUX_CONFIG[sortedID] = tmpAUX_CONFIG[i];
|
||||||
|
AUX_CONFIG_IDS[sortedID++] = tmpAUX_CONFIG_IDS[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||||
|
|
||||||
|
|
|
@ -54,15 +54,15 @@
|
||||||
<table class="cf_table acc">
|
<table class="cf_table acc">
|
||||||
<tr>
|
<tr>
|
||||||
<td data-i18n="accZero"></td>
|
<td data-i18n="accZero"></td>
|
||||||
<td><label for="accZeroX"><span>X</span></label><input type="number" name="accZeroX" min="0" max="2000"></td>
|
<td><label for="accZeroX"><span>X</span></label><input readonly disabled type="number" name="accZeroX" min="-32768" max="32767"></td>
|
||||||
<td><label for="accZeroY"><span>Y</span></label><input type="number" name="accZeroY" min="0" max="2000"></td>
|
<td><label for="accZeroY"><span>Y</span></label><input readonly disabled type="number" name="accZeroY" min="-32768" max="32767"></td>
|
||||||
<td><label for="accZeroZ"><span>Z</span></label><input type="number" name="accZeroZ" min="0" max="2000"></td>
|
<td><label for="accZeroZ"><span>Z</span></label><input readonly disabled type="number" name="accZeroZ" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td data-i18n="accGain"></td>
|
<td data-i18n="accGain"></td>
|
||||||
<td><label for="accGainX"><span>X</span></label><input type="number" name="accGainX" min="0" max="2000"></td>
|
<td><label for="accGainX"><span>X</span></label><input readonly disabled type="number" name="accGainX" min="1" max="8192"></td>
|
||||||
<td><label for="accGainY"><span>Y</span></label><input type="number" name="accGainY" min="0" max="2000"></td>
|
<td><label for="accGainY"><span>Y</span></label><input readonly disabled type="number" name="accGainY" min="1" max="8192"></td>
|
||||||
<td><label for="accGainZ"><span>Z</span></label><input type="number" name="accGainZ" min="0" max="2000"></td>
|
<td><label for="accGainZ"><span>Z</span></label><input readonly disabled type="number" name="accGainZ" min="1" max="8192"></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
@ -99,27 +99,27 @@
|
||||||
<table id="mag-calibrated-data" class="cf_table">
|
<table id="mag-calibrated-data" class="cf_table">
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagX"><span>Zero X</span></label></td>
|
<td><label for="MagX"><span>Zero X</span></label></td>
|
||||||
<td><input type="number" name="MagX" min="0" max="2000"></td>
|
<td><input readonly disabled type="number" name="MagX" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagY"><span>Zero Y</span></label></td>
|
<td><label for="MagY"><span>Zero Y</span></label></td>
|
||||||
<td><input type="number" name="MagY" min="0" max="2000"></td>
|
<td><input readonly disabled type="number" name="MagY" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagZ"><span>Zero Z</span></label></td>
|
<td><label for="MagZ"><span>Zero Z</span></label></td>
|
||||||
<td><input type="number" name="MagZ" min="0" max="2000"></td>
|
<td><input readonly disabled type="number" name="MagZ" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagGainX"><span>Gain X</span></label></td>
|
<td><label for="MagGainX"><span>Gain X</span></label></td>
|
||||||
<td><input type="number" name="MagGainX" min="0" max="2000"></td>
|
<td><input readonly disabled type="number" name="MagGainX" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagGainY"><span>Gain Y</span></label></td>
|
<td><label for="MagGainY"><span>Gain Y</span></label></td>
|
||||||
<td><input type="number" name="MagGainY" min="0" max="2000"></td>
|
<td><input readonly disabled type="number" name="MagGainY" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td><label for="MagGainZ"><span>Gain Z</span></label></td>
|
<td><label for="MagGainZ"><span>Gain Z</span></label></td>
|
||||||
<td><input type="number" name="MagGainZ" min="0" max="2000"></td>
|
<td><input readonly disabled type="number" name="MagGainZ" min="-32768" max="32767"></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -12,7 +12,6 @@
|
||||||
<div class="spacer_box_title" data-i18n="configurationSystem"></div>
|
<div class="spacer_box_title" data-i18n="configurationSystem"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div id="gyrolpf-info" class="info-box is-hidden"></div>
|
|
||||||
<div class="select is-hidden">
|
<div class="select is-hidden">
|
||||||
<select id="gyro-lpf"></select>
|
<select id="gyro-lpf"></select>
|
||||||
<label for="gyro-lpf"> <span data-i18n="configurationGyroLpfTitle"></span></label>
|
<label for="gyro-lpf"> <span data-i18n="configurationGyroLpfTitle"></span></label>
|
||||||
|
@ -82,16 +81,7 @@
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configHelp2"></div>
|
<div class="helpicon cf_tip" data-i18n_title="configHelp2"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="number">
|
<div class="info-box" data-i18n="rollPitchAdjustmentsMoved"></div>
|
||||||
<input type="number" id="board_align_roll" name="board_align_roll" step="0.1" min="-180" max="360" />
|
|
||||||
<div class="alignicon roll"></div>
|
|
||||||
<label for="board_align_roll" data-i18n="configurationBoardAlignmentRoll"></label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="board_align_pitch" name="board_align_pitch" step="0.1" min="-180" max="360" />
|
|
||||||
<div class="alignicon pitch"></div>
|
|
||||||
<label for="board_align_pitch" data-i18n="configurationBoardAlignmentPitch"></label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="board_align_yaw" type="number" name="board_align_yaw" step="0.1" min="-180" max="360" />
|
<input id="board_align_yaw" type="number" name="board_align_yaw" step="0.1" min="-180" max="360" />
|
||||||
<div class="alignicon yaw"></div>
|
<div class="alignicon yaw"></div>
|
||||||
|
@ -253,7 +243,7 @@
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
<div class="config-section 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="configurationBatteryVoltage"></div>
|
<div class="spacer_box_title" data-i18n="configurationVoltageCurrentSensor"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="features batteryVoltage"></div>
|
<div class="features batteryVoltage"></div>
|
||||||
|
@ -273,8 +263,55 @@
|
||||||
</label>
|
</label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationVoltageSourceHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="configurationVoltageSourceHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="cells" name="cells" step="1" min="0" max="8" />
|
<input type="number" id="voltagescale" name="voltagescale" step="1" min="10" max="65535" />
|
||||||
|
<label for="voltagescale">
|
||||||
|
<span data-i18n="configurationBatteryScale"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input type="text" id="batteryvoltage" name="batteryvoltage" readonly class="disabled" />
|
||||||
|
<label for="batteryvoltage">
|
||||||
|
<span data-i18n="configurationBatteryVoltage"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="features batteryCurrent"></div>
|
||||||
|
<div class="select">
|
||||||
|
<select id="current_meter_type" data-setting="current_meter_type" />
|
||||||
|
<label for="current_meter_type">
|
||||||
|
<span data-i18n="configurationCurrentMeterType"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="currentscale" name="currentscale" step="1" min="-10000" max="10000" />
|
||||||
|
<label for="currentscale">
|
||||||
|
<span data-i18n="configurationCurrentScale"></span>
|
||||||
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="configurationCurrentScaleHelp"></div>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="currentoffset" name="currentoffset" step="0.1" min="-3276.8" max="3276.7" />
|
||||||
|
<label for="currentoffset">
|
||||||
|
<span data-i18n="configurationCurrentOffset"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input type="text" id="batterycurrent" name="batterycurrent" readonly class="disabled" />
|
||||||
|
<label for="batterycurrent">
|
||||||
|
<span data-i18n="configurationBatteryCurrent"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="config-section gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="configurationBatterySettings"></div>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="configurationBatterySettingsHelp"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="cells" name="cells" step="1" min="0" max="12" />
|
||||||
<label for="cells"><span data-i18n="configurationBatteryCells"></span></label>
|
<label for="cells"><span data-i18n="configurationBatteryCells"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellsHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellsHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -299,62 +336,14 @@
|
||||||
<span data-i18n="configurationBatteryWarning"></span>
|
<span data-i18n="configurationBatteryWarning"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="voltagescale" name="voltagescale" step="1" min="10" max="65535" />
|
|
||||||
<label for="voltagescale">
|
|
||||||
<span data-i18n="configurationBatteryScale"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="text" id="batteryvoltage" name="batteryvoltage" readonly class="disabled" />
|
|
||||||
<label for="batteryvoltage">
|
|
||||||
<span data-i18n="configurationBatteryVoltage"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="config-section gui_box grey">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="configurationCurrent"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="features batteryCurrent"></div>
|
|
||||||
<div class="select">
|
|
||||||
<select id="current_meter_type" data-setting="current_meter_type" />
|
|
||||||
<label for="current_meter_type">
|
|
||||||
<span data-i18n="configurationCurrentMeterType"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="currentscale" name="currentscale" step="1" min="-10000" max="10000" />
|
|
||||||
<label for="currentscale">
|
|
||||||
<span data-i18n="configurationCurrentScale"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="currentoffset" name="currentoffset" step="0.1" min="-3276.8" max="3276.7" />
|
|
||||||
<label for="currentoffset">
|
|
||||||
<span data-i18n="configurationCurrentOffset"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="text" id="batterycurrent" name="batterycurrent" readonly class="disabled" />
|
|
||||||
<label for="batterycurrent">
|
|
||||||
<span data-i18n="configurationBatteryCurrent"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="config-section gui_box grey">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="configurationBatteryCapacity"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="select">
|
<div class="select">
|
||||||
<select id="battery_capacity_unit">
|
<select id="battery_capacity_unit">
|
||||||
<option value="mAh">mAh</option>
|
<option value="mAh">mAh</option>
|
||||||
<option value="mWh">mWh</option>
|
<option value="mWh">mWh</option>
|
||||||
</select>
|
</select>
|
||||||
|
<label for="warningcellvoltage">
|
||||||
|
<span data-i18n="configurationBatteryCapacityUnit"></span>
|
||||||
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="battery_capacity" name="battery_capacity" step="1" min="0" max="4294967296" />
|
<input type="number" id="battery_capacity" name="battery_capacity" step="1" min="0" max="4294967296" />
|
||||||
|
|
|
@ -257,8 +257,6 @@ 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_roll"]').val((BF_CONFIG.board_align_roll / 10.0).toFixed(1));
|
|
||||||
$('input[name="board_align_pitch"]').val((BF_CONFIG.board_align_pitch / 10.0).toFixed(1));
|
|
||||||
$('input[name="board_align_yaw"]').val((BF_CONFIG.board_align_yaw / 10.0).toFixed(1));
|
$('input[name="board_align_yaw"]').val((BF_CONFIG.board_align_yaw / 10.0).toFixed(1));
|
||||||
|
|
||||||
// fill magnetometer
|
// fill magnetometer
|
||||||
|
@ -316,12 +314,9 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
$i2cSpeed.change();
|
$i2cSpeed.change();
|
||||||
|
|
||||||
var $looptime = $("#looptime");
|
let $looptime = $("#looptime"),
|
||||||
|
$gyroLpf = $("#gyro-lpf"),
|
||||||
var $gyroLpf = $("#gyro-lpf"),
|
values = FC.getGyroLpfValues();
|
||||||
$gyroLpfMessage = $('#gyrolpf-info');
|
|
||||||
|
|
||||||
var values = FC.getGyroLpfValues();
|
|
||||||
|
|
||||||
for (i in values) {
|
for (i in values) {
|
||||||
if (values.hasOwnProperty(i)) {
|
if (values.hasOwnProperty(i)) {
|
||||||
|
@ -343,43 +338,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
);
|
);
|
||||||
$looptime.val(FC.getLooptimes()[FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick].defaultLooptime);
|
$looptime.val(FC.getLooptimes()[FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick].defaultLooptime);
|
||||||
$looptime.change();
|
$looptime.change();
|
||||||
|
|
||||||
$gyroLpfMessage.hide();
|
|
||||||
$gyroLpfMessage.removeClass('ok-box');
|
|
||||||
$gyroLpfMessage.removeClass('info-box');
|
|
||||||
$gyroLpfMessage.removeClass('warning-box');
|
|
||||||
|
|
||||||
if (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) {
|
|
||||||
switch (parseInt(INAV_PID_CONFIG.gyroscopeLpf, 10)) {
|
|
||||||
case 0:
|
|
||||||
$gyroLpfMessage.html(chrome.i18n.getMessage('gyroLpfSuggestedMessage'));
|
|
||||||
$gyroLpfMessage.addClass('ok-box');
|
|
||||||
$gyroLpfMessage.show();
|
|
||||||
break;
|
|
||||||
case 1:
|
|
||||||
$gyroLpfMessage.html(chrome.i18n.getMessage('gyroLpfWhyNotHigherMessage'));
|
|
||||||
$gyroLpfMessage.addClass('info-box');
|
|
||||||
$gyroLpfMessage.show();
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
$gyroLpfMessage.html(chrome.i18n.getMessage('gyroLpfWhyNotSlightlyHigherMessage'));
|
|
||||||
$gyroLpfMessage.addClass('info-box');
|
|
||||||
$gyroLpfMessage.show();
|
|
||||||
break
|
|
||||||
case 3:
|
|
||||||
$gyroLpfMessage.html(chrome.i18n.getMessage('gyroLpfNotAdvisedMessage'));
|
|
||||||
$gyroLpfMessage.addClass('info-box');
|
|
||||||
$gyroLpfMessage.show();
|
|
||||||
break;
|
|
||||||
case 4:
|
|
||||||
case 5:
|
|
||||||
$gyroLpfMessage.html(chrome.i18n.getMessage('gyroLpfNotFlyableMessage'));
|
|
||||||
$gyroLpfMessage.addClass('warning-box');
|
|
||||||
$gyroLpfMessage.show();
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
$gyroLpf.change();
|
$gyroLpf.change();
|
||||||
|
@ -393,11 +351,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
} else {
|
} else {
|
||||||
$('#looptime-warning').hide();
|
$('#looptime-warning').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (INAV_PID_CONFIG.asynchronousMode == 0) {
|
|
||||||
//All task running together
|
|
||||||
ADVANCED_CONFIG.gyroSyncDenominator = Math.floor(FC_CONFIG.loopTime / FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick);
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
$looptime.change();
|
$looptime.change();
|
||||||
|
|
||||||
|
@ -512,8 +465,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
helper.features.reset();
|
helper.features.reset();
|
||||||
helper.features.fromUI($('.tab-configuration'));
|
helper.features.fromUI($('.tab-configuration'));
|
||||||
helper.features.execute(function () {
|
helper.features.execute(function () {
|
||||||
BF_CONFIG.board_align_roll = Math.round(parseFloat($('input[name="board_align_roll"]').val()) * 10);
|
|
||||||
BF_CONFIG.board_align_pitch = Math.round(parseFloat($('input[name="board_align_pitch"]').val()) * 10);
|
|
||||||
BF_CONFIG.board_align_yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
|
BF_CONFIG.board_align_yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
|
||||||
BF_CONFIG.currentscale = parseInt($('#currentscale').val());
|
BF_CONFIG.currentscale = parseInt($('#currentscale').val());
|
||||||
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
|
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
|
||||||
|
|
|
@ -139,7 +139,7 @@ TABS.firmware_flasher.initialize = function (callback) {
|
||||||
TABS.firmware_flasher.releases = releases;
|
TABS.firmware_flasher.releases = releases;
|
||||||
};
|
};
|
||||||
|
|
||||||
$.get('https://api.github.com/repos/iNavFlight/inav/releases', function (releasesData){
|
$.get('https://api.github.com/repos/iNavFlight/inav/releases?per_page=10', function (releasesData){
|
||||||
TABS.firmware_flasher.releasesData = releasesData;
|
TABS.firmware_flasher.releasesData = releasesData;
|
||||||
buildBoardOptions();
|
buildBoardOptions();
|
||||||
|
|
||||||
|
|
|
@ -86,7 +86,7 @@
|
||||||
<div class="spacer_box_title" data-i18n="gpsMapHead"></div>
|
<div class="spacer_box_title" data-i18n="gpsMapHead"></div>
|
||||||
</div>
|
</div>
|
||||||
<div id="loadmap">
|
<div id="loadmap">
|
||||||
<div id="gps-map">
|
<div style="height:100%" id="gps-map">
|
||||||
<button class="map-button" id="center_button" data-i18n="gps_map_center"></button>
|
<button class="map-button" id="center_button" data-i18n="gps_map_center"></button>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -217,7 +217,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="cf_column threefourth_left">
|
<div class="cf_column threefourth_left">
|
||||||
<div id="missionMap"></div>
|
<div style="height:100%" id="missionMap"></div>
|
||||||
<div id="notLoadMap" data-i18n="useOnlyStandalone" style="display: none;"></div>
|
<div id="notLoadMap" data-i18n="useOnlyStandalone" style="display: none;"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -68,9 +68,14 @@
|
||||||
<label>
|
<label>
|
||||||
<select class="update_preview" data-setting="osd_coordinate_digits" data-live="true"></select> Coordinate Digits
|
<select class="update_preview" data-setting="osd_coordinate_digits" data-live="true"></select> Coordinate Digits
|
||||||
</label>
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="osdSettingPLUS_CODE_DIGITS_HELP"></div>
|
||||||
<label>
|
<label>
|
||||||
<select class="update_preview" data-setting="osd_plus_code_digits" data-live="true"></select> Plus Code Digits
|
<select class="update_preview" data-setting="osd_plus_code_digits" data-live="true"></select> Plus Code Digits
|
||||||
</label>
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="osdSettingPLUS_CODE_SHORT_HELP"></div>
|
||||||
|
<label>
|
||||||
|
<select class="update_preview" data-setting="osd_plus_code_short" data-live="true"></select> Plus Code Remove Leading Digits
|
||||||
|
</label>
|
||||||
<label>
|
<label>
|
||||||
<select class="update_preview" data-setting="osd_crosshairs_style" data-live="true"></select> Crosshairs Style
|
<select class="update_preview" data-setting="osd_crosshairs_style" data-live="true"></select> Crosshairs Style
|
||||||
</label>
|
</label>
|
||||||
|
@ -87,6 +92,9 @@
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" class="toggle update_preview" data-setting="osd_sidebar_scroll_arrows" data-live="true"> Sidebar Scroll Arrows
|
<input type="checkbox" class="toggle update_preview" data-setting="osd_sidebar_scroll_arrows" data-live="true"> Sidebar Scroll Arrows
|
||||||
</label>
|
</label>
|
||||||
|
<label>
|
||||||
|
<input type="checkbox" class="toggle update_preview" data-setting="osd_home_position_arm_screen" data-live="true"> Home Position on Arming Screen
|
||||||
|
</label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
18
tabs/osd.js
18
tabs/osd.js
|
@ -963,6 +963,11 @@ OSD.constants = {
|
||||||
}
|
}
|
||||||
return FONT.embed_dot('-0.5') + FONT.symbol(SYM.M_S);
|
return FONT.embed_dot('-0.5') + FONT.symbol(SYM.M_S);
|
||||||
}
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
name: 'OSD_RANGEFINDER',
|
||||||
|
id: 120,
|
||||||
|
preview: "2" + FONT.symbol(SYM.DIST_KM)
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
@ -1191,8 +1196,9 @@ OSD.constants = {
|
||||||
id: 97,
|
id: 97,
|
||||||
preview: function() {
|
preview: function() {
|
||||||
let digits = parseInt(Settings.getInputValue('osd_plus_code_digits')) + 1;
|
let digits = parseInt(Settings.getInputValue('osd_plus_code_digits')) + 1;
|
||||||
|
let digitsRemoved = parseInt(Settings.getInputValue('osd_plus_code_short')) * 2;
|
||||||
console.log("DITIS", digits);
|
console.log("DITIS", digits);
|
||||||
return '9547X6PM+VWCCC'.substr(0, digits);
|
return '9547X6PM+VWCCC'.substr(digitsRemoved, digits-digitsRemoved);
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -1285,12 +1291,12 @@ OSD.constants = {
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: 'CRUISE_HEADING_ERROR',
|
name: 'COURSE_HOLD_ERROR',
|
||||||
id: 51,
|
id: 51,
|
||||||
preview: FONT.symbol(SYM.HEADING) + ' 5' + FONT.symbol(SYM.DEGREES)
|
preview: FONT.symbol(SYM.HEADING) + ' 5' + FONT.symbol(SYM.DEGREES)
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: 'CRUISE_HEADING_ADJUSTMENT',
|
name: 'COURSE_HOLD_ADJUSTMENT',
|
||||||
id: 52,
|
id: 52,
|
||||||
preview: FONT.symbol(SYM.HEADING) + ' -90' + FONT.symbol(SYM.DEGREES)
|
preview: FONT.symbol(SYM.HEADING) + ' -90' + FONT.symbol(SYM.DEGREES)
|
||||||
},
|
},
|
||||||
|
@ -1424,17 +1430,17 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'ROLL_PIDS',
|
name: 'ROLL_PIDS',
|
||||||
id: 16,
|
id: 16,
|
||||||
preview: 'ROL 40 30 23'
|
preview: 'ROL 40 30 20 23'
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: 'PITCH_PIDS',
|
name: 'PITCH_PIDS',
|
||||||
id: 17,
|
id: 17,
|
||||||
preview: 'PIT 40 30 23'
|
preview: 'PIT 40 30 20 23'
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: 'YAW_PIDS',
|
name: 'YAW_PIDS',
|
||||||
id: 18,
|
id: 18,
|
||||||
preview: 'YAW 85 45 0'
|
preview: 'YAW 85 45 0 20'
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: 'LEVEL_PIDS',
|
name: 'LEVEL_PIDS',
|
||||||
|
|
|
@ -164,27 +164,6 @@
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="clear-both"></div>
|
|
||||||
<div class="cf_column" style="margin-top:1em;">
|
|
||||||
<table class="settings-table settings-table--misc">
|
|
||||||
<tr>
|
|
||||||
<th data-i18n="pidTuningTPA"></th>
|
|
||||||
<td>
|
|
||||||
<input type="number" class="rate-tpa_input" id="tpa" step="1" min="0" max="100" />
|
|
||||||
%
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="pidTuningTPAHelp"></div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<th data-i18n="pidTuningTPABreakPoint"></th>
|
|
||||||
<td>
|
|
||||||
<input type="number" class="rate-tpa_input" id="tpa-breakpoint" step="10" min="1000"
|
|
||||||
max="2000" />
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="pidTuningTPABreakPointHelp"></div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="subtab-rates" class="subtab__content">
|
<div id="subtab-rates" class="subtab__content">
|
||||||
|
@ -481,17 +460,17 @@
|
||||||
<table class="settings-table settings-table--filtering">
|
<table class="settings-table settings-table--filtering">
|
||||||
<tbody>
|
<tbody>
|
||||||
<tr>
|
<tr>
|
||||||
<th data-i18n="mc_airmode_type"></th>
|
<th data-i18n="airmode_type"></th>
|
||||||
<td>
|
<td>
|
||||||
<select data-setting="mc_airmode_type" />
|
<select data-setting="airmode_type" />
|
||||||
<div class="helpicon cf_tip" data-i18n_title="mc_airmode_type_help"></div>
|
<div class="helpicon cf_tip" data-i18n_title="airmode_type_help"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<th data-i18n="mc_airmode_threshold"></th>
|
<th data-i18n="airmode_throttle_threshold"></th>
|
||||||
<td>
|
<td>
|
||||||
<select data-setting="mc_airmode_threshold" />
|
<select data-setting="airmode_throttle_threshold" />
|
||||||
<div class="helpicon cf_tip" data-i18n_title="mc_airmode_threshold_help"></div>
|
<div class="helpicon cf_tip" data-i18n_title="airmode_throttle_threshold_help"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
|
@ -526,6 +505,13 @@
|
||||||
<input class="rate-tpa_input" data-setting="antigravity_cutoff_lpf_hz" />
|
<input class="rate-tpa_input" data-setting="antigravity_cutoff_lpf_hz" />
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="itermBankAngleFreeze"></th>
|
||||||
|
<td>
|
||||||
|
<input class="rate-tpa_input" data-setting="fw_yaw_iterm_freeze_bank_angle" type="number" step="1" min="0" max="90" />
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="itermBankAngleFreezeHelp"></div>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
@ -559,6 +545,44 @@
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
<div class="tab_subtitle" data-i18n="tpaMechanics" style="margin-top: 1em;"></div>
|
||||||
|
<div class="cf_column" style="margin-top:1em;">
|
||||||
|
<table class="settings-table settings-table--misc">
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="pidTuningTPA"></th>
|
||||||
|
<td>
|
||||||
|
<input type="number" class="rate-tpa_input" id="tpa" step="1" min="0" max="100" />
|
||||||
|
%
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="pidTuningTPAHelp"></div>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="pidTuningTPABreakPoint"></th>
|
||||||
|
<td>
|
||||||
|
<input type="number" class="rate-tpa_input" id="tpa-breakpoint" step="10" min="1000"
|
||||||
|
max="2000" />
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="pidTuningTPABreakPointHelp"></div>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
<div class="tab_subtitle" data-i18n="fwLevelTrimMechanics" style="margin-top: 1em;"></div>
|
||||||
|
<div class="cf_column">
|
||||||
|
<table class="settings-table settings-table--filtering">
|
||||||
|
<tbody>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="fw_level_pitch_trim"></th>
|
||||||
|
<td>
|
||||||
|
<input data-setting="fw_level_pitch_trim" class="rate-tpa_input" />
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="fw_level_pitch_trim_help"></div>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</tbody>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
|
|
|
@ -99,6 +99,12 @@ TABS.ports.initialize = function (callback) {
|
||||||
maxPorts: 1 }
|
maxPorts: 1 }
|
||||||
);
|
);
|
||||||
|
|
||||||
|
functionRules.push({
|
||||||
|
name: 'IMU2',
|
||||||
|
groups: ['peripherals'],
|
||||||
|
maxPorts: 1 }
|
||||||
|
);
|
||||||
|
|
||||||
for (var i = 0; i < functionRules.length; i++) {
|
for (var i = 0; i < functionRules.length; i++) {
|
||||||
functionRules[i].displayName = chrome.i18n.getMessage('portsFunction_' + functionRules[i].name);
|
functionRules[i].displayName = chrome.i18n.getMessage('portsFunction_' + functionRules[i].name);
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,6 +1,12 @@
|
||||||
<div class="tab-configuration tab-programming toolbar_fixed_bottom">
|
<div class="tab-configuration tab-programming toolbar_fixed_bottom">
|
||||||
<div class="content_wrapper" id="programming-main-content">
|
<div class="content_wrapper" id="programming-main-content">
|
||||||
|
|
||||||
|
|
||||||
|
<div class="tab_title subtab__header">
|
||||||
|
<span class="subtab__header_label subtab__header_label--current" for="subtab-lc">Logic Conditions</span>
|
||||||
|
<span class="subtab__header_label" for="subtab-pid">PID Controllers</span>
|
||||||
|
</div>
|
||||||
|
|
||||||
<div class="gvar__container">
|
<div class="gvar__container">
|
||||||
<div class="gvar__wrapper">
|
<div class="gvar__wrapper">
|
||||||
<div class="gvar__cell">
|
<div class="gvar__cell">
|
||||||
|
@ -9,24 +15,45 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<table class="mixer-table logic__table">
|
|
||||||
<thead>
|
|
||||||
<tr>
|
|
||||||
<th style="width: 50px" data-i18n="logicId"></th>
|
|
||||||
<th style="width: 80px" data-i18n="logicEnabled"></th>
|
|
||||||
<th style="width: 120px" data-i18n="logicOperation"></th>
|
|
||||||
<th data-i18n="logicOperandA"></th>
|
|
||||||
<th data-i18n="logicOperandB"></th>
|
|
||||||
<th data-i18n="logicActivator"></th>
|
|
||||||
<th style="width: 40px" data-i18n="logicFlags"></th>
|
|
||||||
<th style="width: 50px" data-i18n="logicStatus"></th>
|
|
||||||
</tr>
|
|
||||||
</thead>
|
|
||||||
<tbody>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
|
|
||||||
|
<div id="subtab-lc" class="subtab__content subtab__content--current">
|
||||||
|
<table class="mixer-table logic__table">
|
||||||
|
<thead>
|
||||||
|
<tr>
|
||||||
|
<th style="width: 50px" data-i18n="logicId"></th>
|
||||||
|
<th style="width: 80px" data-i18n="logicEnabled"></th>
|
||||||
|
<th style="width: 120px" data-i18n="logicOperation"></th>
|
||||||
|
<th data-i18n="logicOperandA"></th>
|
||||||
|
<th data-i18n="logicOperandB"></th>
|
||||||
|
<th data-i18n="logicActivator"></th>
|
||||||
|
<th style="width: 40px" data-i18n="logicFlags"></th>
|
||||||
|
<th style="width: 50px" data-i18n="logicStatus"></th>
|
||||||
|
</tr>
|
||||||
|
</thead>
|
||||||
|
<tbody>
|
||||||
|
</tbody>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div id="subtab-pid" class="subtab__content">
|
||||||
|
<table class="mixer-table pid__table">
|
||||||
|
<thead>
|
||||||
|
<tr>
|
||||||
|
<th style="width: 50px" data-i18n="pidId"></th>
|
||||||
|
<th style="width: 80px" data-i18n="pidEnabled"></th>
|
||||||
|
<th data-i18n="pidSetpoint"></th>
|
||||||
|
<th data-i18n="pidMeasurement"></th>
|
||||||
|
<th style="width: 80px" data-i18n="pidP"></th>
|
||||||
|
<th style="width: 80px" data-i18n="pidI"></th>
|
||||||
|
<th style="width: 80px" data-i18n="pidD"></th>
|
||||||
|
<th style="width: 80px" data-i18n="pidFF"></th>
|
||||||
|
<th style="width: 80px" data-i18n="pidOutput"></th>
|
||||||
|
</tr>
|
||||||
|
</thead>
|
||||||
|
<tbody>
|
||||||
|
</tbody>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_toolbar">
|
<div class="content_toolbar">
|
||||||
<div class="btn save_btn">
|
<div class="btn save_btn">
|
||||||
|
|
|
@ -14,19 +14,23 @@ TABS.programming.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
loadChainer.setChain([
|
loadChainer.setChain([
|
||||||
mspHelper.loadLogicConditions,
|
mspHelper.loadLogicConditions,
|
||||||
mspHelper.loadGlobalVariablesStatus
|
mspHelper.loadGlobalVariablesStatus,
|
||||||
|
mspHelper.loadProgrammingPidStatus,
|
||||||
|
mspHelper.loadProgrammingPid
|
||||||
]);
|
]);
|
||||||
loadChainer.setExitPoint(loadHtml);
|
loadChainer.setExitPoint(loadHtml);
|
||||||
loadChainer.execute();
|
loadChainer.execute();
|
||||||
|
|
||||||
saveChainer.setChain([
|
saveChainer.setChain([
|
||||||
mspHelper.sendLogicConditions,
|
mspHelper.sendLogicConditions,
|
||||||
|
mspHelper.sendProgrammingPid,
|
||||||
mspHelper.saveToEeprom
|
mspHelper.saveToEeprom
|
||||||
]);
|
]);
|
||||||
|
|
||||||
statusChainer.setChain([
|
statusChainer.setChain([
|
||||||
mspHelper.loadLogicConditionsStatus,
|
mspHelper.loadLogicConditionsStatus,
|
||||||
mspHelper.loadGlobalVariablesStatus
|
mspHelper.loadGlobalVariablesStatus,
|
||||||
|
mspHelper.loadProgrammingPidStatus
|
||||||
]);
|
]);
|
||||||
statusChainer.setExitPoint(onStatusPullDone);
|
statusChainer.setExitPoint(onStatusPullDone);
|
||||||
|
|
||||||
|
@ -36,9 +40,12 @@ TABS.programming.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
function processHtml() {
|
function processHtml() {
|
||||||
|
|
||||||
LOGIC_CONDITIONS.init($('#programming-main-content'));
|
LOGIC_CONDITIONS.init($('#subtab-lc'));
|
||||||
LOGIC_CONDITIONS.render();
|
LOGIC_CONDITIONS.render();
|
||||||
|
|
||||||
|
PROGRAMMING_PID.init($('#subtab-pid'));
|
||||||
|
PROGRAMMING_PID.render();
|
||||||
|
|
||||||
GLOBAL_VARIABLES_STATUS.init($(".gvar__container"));
|
GLOBAL_VARIABLES_STATUS.init($(".gvar__container"));
|
||||||
|
|
||||||
helper.tabs.init($('.tab-programming'));
|
helper.tabs.init($('.tab-programming'));
|
||||||
|
@ -59,6 +66,7 @@ TABS.programming.initialize = function (callback, scrollPosition) {
|
||||||
function onStatusPullDone() {
|
function onStatusPullDone() {
|
||||||
LOGIC_CONDITIONS.update(LOGIC_CONDITIONS_STATUS);
|
LOGIC_CONDITIONS.update(LOGIC_CONDITIONS_STATUS);
|
||||||
GLOBAL_VARIABLES_STATUS.update($('.tab-programming'));
|
GLOBAL_VARIABLES_STATUS.update($('.tab-programming'));
|
||||||
|
PROGRAMMING_PID.update(PROGRAMMING_PID_STATUS);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue