mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-14 03:49:53 +03:00
Merge branch 'master' into MrD-Highlight-parameters-that-change-with-profiles-or-battery-profiles
This commit is contained in:
commit
e7c7f2d342
17 changed files with 490 additions and 315 deletions
|
@ -2129,7 +2129,7 @@
|
||||||
"message": "<strong>Note:</strong> When Stage 2 is DISABLED, the fallback setting <strong>Auto</strong> is used instead of the user settings for all flightchannels (Roll, Pitch, Yaw and Throttle)."
|
"message": "<strong>Note:</strong> When Stage 2 is DISABLED, the fallback setting <strong>Auto</strong> is used instead of the user settings for all flightchannels (Roll, Pitch, Yaw and Throttle)."
|
||||||
},
|
},
|
||||||
"failsafeDelayItem": {
|
"failsafeDelayItem": {
|
||||||
"message": "Guard time for activation after signal lost [1 = 0.1 sec.]"
|
"message": "Guard time for activation after signal lost [For deciseconds (ds): 1 = 0.1 sec.]"
|
||||||
},
|
},
|
||||||
"failsafeDelayHelp": {
|
"failsafeDelayHelp": {
|
||||||
"message": "Time for stage 1 to wait for recovery"
|
"message": "Time for stage 1 to wait for recovery"
|
||||||
|
@ -2138,7 +2138,7 @@
|
||||||
"message": "Throttle value used while landing"
|
"message": "Throttle value used while landing"
|
||||||
},
|
},
|
||||||
"failsafeOffDelayItem": {
|
"failsafeOffDelayItem": {
|
||||||
"message": "Delay for turning off the Motors during Failsafe [1 = 0.1 sec.]"
|
"message": "Delay for turning off the Motors during Failsafe [For deciseconds (ds):1 = 0.1 sec.]"
|
||||||
},
|
},
|
||||||
"failsafeOffDelayHelp": {
|
"failsafeOffDelayHelp": {
|
||||||
"message": "Time to stay in landing mode untill the motors are turned off and the craft is disarmed"
|
"message": "Time to stay in landing mode untill the motors are turned off and the craft is disarmed"
|
||||||
|
@ -2897,16 +2897,16 @@
|
||||||
"message": "Fly Time (minutes)"
|
"message": "Fly Time (minutes)"
|
||||||
},
|
},
|
||||||
"osd_alt_alarm": {
|
"osd_alt_alarm": {
|
||||||
"message": "Altitude (meters)"
|
"message": "Altitude"
|
||||||
},
|
},
|
||||||
"osd_dist_alarm": {
|
"osd_dist_alarm": {
|
||||||
"message": "Distance (meters)"
|
"message": "Distance"
|
||||||
},
|
},
|
||||||
"osdAlarmDIST_HELP": {
|
"osdAlarmDIST_HELP": {
|
||||||
"message": "The distance to home indicator will flash when the distance is greater than this value. Zero disables this alarm."
|
"message": "The distance to home indicator will flash when the distance is greater than this value. Zero disables this alarm."
|
||||||
},
|
},
|
||||||
"osd_neg_alt_alarm": {
|
"osd_neg_alt_alarm": {
|
||||||
"message": "Negative Altitude (meters)"
|
"message": "Negative Altitude"
|
||||||
},
|
},
|
||||||
"osdAlarmMAX_NEG_ALTITUDE_HELP": {
|
"osdAlarmMAX_NEG_ALTITUDE_HELP": {
|
||||||
"message": "The altitude indicator will flash when altitude is negative and its absolute value is greater than this alarm. Useful when taking off from elevated places. Zero disables this alarm."
|
"message": "The altitude indicator will flash when altitude is negative and its absolute value is greater than this alarm. Useful when taking off from elevated places. Zero disables this alarm."
|
||||||
|
|
307
js/model.js
307
js/model.js
|
@ -44,6 +44,7 @@ const
|
||||||
|
|
||||||
// generate mixer
|
// generate mixer
|
||||||
const mixerList = [
|
const mixerList = [
|
||||||
|
// ** Multirotor
|
||||||
{
|
{
|
||||||
id: 1,
|
id: 1,
|
||||||
name: 'Tricopter',
|
name: 'Tricopter',
|
||||||
|
@ -60,7 +61,7 @@ const mixerList = [
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
]
|
]
|
||||||
}, // 1
|
}, // 1
|
||||||
{
|
{
|
||||||
id: 3,
|
id: 3,
|
||||||
name: 'Quad X',
|
name: 'Quad X',
|
||||||
|
@ -76,7 +77,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, -1.0, -1.0), // FRONT_L
|
new MotorMixRule(1.0, 1.0, -1.0, -1.0), // FRONT_L
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 3
|
}, // 3
|
||||||
{
|
{
|
||||||
id: 2,
|
id: 2,
|
||||||
name: 'Quad +',
|
name: 'Quad +',
|
||||||
|
@ -92,7 +93,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 0.0, -1.0, -1.0), // FRONT
|
new MotorMixRule(1.0, 0.0, -1.0, -1.0), // FRONT
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 2
|
}, // 2
|
||||||
{
|
{
|
||||||
id: 4,
|
id: 4,
|
||||||
name: 'Bicopter',
|
name: 'Bicopter',
|
||||||
|
@ -103,18 +104,7 @@ const mixerList = [
|
||||||
platform: PLATFORM_MULTIROTOR,
|
platform: PLATFORM_MULTIROTOR,
|
||||||
motorMixer: [],
|
motorMixer: [],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 4
|
}, // 4
|
||||||
{
|
|
||||||
id: 5,
|
|
||||||
name: 'Gimbal',
|
|
||||||
model: 'custom',
|
|
||||||
image: 'custom',
|
|
||||||
enabled: false,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_OTHER,
|
|
||||||
motorMixer: [],
|
|
||||||
servoMixer: []
|
|
||||||
}, // 5
|
|
||||||
{
|
{
|
||||||
id: 6,
|
id: 6,
|
||||||
name: 'Y6',
|
name: 'Y6',
|
||||||
|
@ -132,7 +122,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, -0.666667, 1.0), // UNDER_LEFT
|
new MotorMixRule(1.0, 1.0, -0.666667, 1.0), // UNDER_LEFT
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 6
|
}, // 6
|
||||||
{
|
{
|
||||||
id: 7,
|
id: 7,
|
||||||
name: 'Hex +',
|
name: 'Hex +',
|
||||||
|
@ -150,45 +140,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 0.0, 1.0, -1.0), // REAR
|
new MotorMixRule(1.0, 0.0, 1.0, -1.0), // REAR
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 7
|
}, // 7
|
||||||
{
|
|
||||||
id: 8,
|
|
||||||
name: 'Flying Wing',
|
|
||||||
model: 'flying_wing',
|
|
||||||
image: 'flying_wing',
|
|
||||||
enabled: true,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_AIRPLANE,
|
|
||||||
motorMixer: [
|
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
|
||||||
],
|
|
||||||
servoMixer: [
|
|
||||||
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
|
||||||
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
|
||||||
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
|
||||||
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
|
||||||
]
|
|
||||||
}, // 8
|
|
||||||
{
|
|
||||||
id: 27,
|
|
||||||
name: 'Flying Wing with differential thrust',
|
|
||||||
model: 'flying_wing',
|
|
||||||
image: 'flying_wing',
|
|
||||||
enabled: true,
|
|
||||||
legacy: false,
|
|
||||||
platform: PLATFORM_AIRPLANE,
|
|
||||||
motorMixer: [
|
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
|
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
|
|
||||||
],
|
|
||||||
servoMixer: [
|
|
||||||
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
|
||||||
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
|
||||||
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
|
||||||
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
|
||||||
]
|
|
||||||
}, // 27
|
|
||||||
{
|
{
|
||||||
id: 9,
|
id: 9,
|
||||||
name: 'Y4',
|
name: 'Y4',
|
||||||
|
@ -204,7 +156,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, -1.0, 0.0), // FRONT_L CW
|
new MotorMixRule(1.0, 1.0, -1.0, 0.0), // FRONT_L CW
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 9
|
}, // 9
|
||||||
{
|
{
|
||||||
id: 10,
|
id: 10,
|
||||||
name: 'Hex X',
|
name: 'Hex X',
|
||||||
|
@ -222,7 +174,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, 0.0, 1.0), // LEFT
|
new MotorMixRule(1.0, 1.0, 0.0, 1.0), // LEFT
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 10
|
}, // 10
|
||||||
{
|
{
|
||||||
id: 11,
|
id: 11,
|
||||||
name: 'Octo X8',
|
name: 'Octo X8',
|
||||||
|
@ -242,7 +194,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, -1.0, 1.0), // UNDER_FRONT_L
|
new MotorMixRule(1.0, 1.0, -1.0, 1.0), // UNDER_FRONT_L
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 11
|
}, // 11
|
||||||
{
|
{
|
||||||
id: 12,
|
id: 12,
|
||||||
name: 'Octo Flat +',
|
name: 'Octo Flat +',
|
||||||
|
@ -262,7 +214,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, 0.0, -1.0), // LEFT
|
new MotorMixRule(1.0, 1.0, 0.0, -1.0), // LEFT
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 12
|
}, // 12
|
||||||
{
|
{
|
||||||
id: 13,
|
id: 13,
|
||||||
name: 'Octo Flat X',
|
name: 'Octo Flat X',
|
||||||
|
@ -282,51 +234,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 1.0, 0.414178, -1.0), // MIDREAR_L
|
new MotorMixRule(1.0, 1.0, 0.414178, -1.0), // MIDREAR_L
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 13
|
}, // 13
|
||||||
{
|
|
||||||
id: 14,
|
|
||||||
name: 'Airplane',
|
|
||||||
model: 'twin_plane',
|
|
||||||
image: 'airplane',
|
|
||||||
enabled: true,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_AIRPLANE,
|
|
||||||
hasFlaps: true,
|
|
||||||
motorMixer: [
|
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
|
||||||
],
|
|
||||||
servoMixer: [
|
|
||||||
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
|
||||||
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
|
||||||
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
|
|
||||||
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
|
||||||
]
|
|
||||||
}, // 14
|
|
||||||
{
|
|
||||||
id: 15,
|
|
||||||
name: 'Heli 120',
|
|
||||||
model: 'custom',
|
|
||||||
image: 'custom',
|
|
||||||
enabled: false,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_HELICOPTER,
|
|
||||||
motorMixer: [],
|
|
||||||
servoMixer: []
|
|
||||||
}, // 15
|
|
||||||
{
|
|
||||||
id: 16,
|
|
||||||
name: 'Heli 90',
|
|
||||||
model: 'custom',
|
|
||||||
image: 'custom',
|
|
||||||
enabled: false,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_HELICOPTER,
|
|
||||||
motorMixer: [],
|
|
||||||
servoMixer: []
|
|
||||||
}, // 16
|
|
||||||
{
|
{
|
||||||
id: 17,
|
id: 17,
|
||||||
name: 'V-tail Quad',
|
name: 'V-tail Quad',
|
||||||
|
@ -360,18 +268,7 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0), // LEFT
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0), // LEFT
|
||||||
],
|
],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 18
|
}, // 18
|
||||||
{
|
|
||||||
id: 19,
|
|
||||||
name: 'PPM to SERVO',
|
|
||||||
model: 'custom',
|
|
||||||
image: 'custom',
|
|
||||||
enabled: false,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_OTHER,
|
|
||||||
motorMixer: [],
|
|
||||||
servoMixer: []
|
|
||||||
}, // 19
|
|
||||||
{
|
{
|
||||||
id: 20,
|
id: 20,
|
||||||
name: 'Dualcopter',
|
name: 'Dualcopter',
|
||||||
|
@ -382,7 +279,7 @@ const mixerList = [
|
||||||
platform: PLATFORM_MULTIROTOR,
|
platform: PLATFORM_MULTIROTOR,
|
||||||
motorMixer: [],
|
motorMixer: [],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 20
|
}, // 20
|
||||||
{
|
{
|
||||||
id: 21,
|
id: 21,
|
||||||
name: 'Singlecopter',
|
name: 'Singlecopter',
|
||||||
|
@ -393,7 +290,7 @@ const mixerList = [
|
||||||
platform: PLATFORM_MULTIROTOR,
|
platform: PLATFORM_MULTIROTOR,
|
||||||
motorMixer: [],
|
motorMixer: [],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 21
|
}, // 21
|
||||||
{
|
{
|
||||||
id: 22,
|
id: 22,
|
||||||
name: 'A-tail Quad',
|
name: 'A-tail Quad',
|
||||||
|
@ -420,18 +317,7 @@ const mixerList = [
|
||||||
platform: PLATFORM_MULTIROTOR,
|
platform: PLATFORM_MULTIROTOR,
|
||||||
motorMixer: [],
|
motorMixer: [],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 23
|
}, // 23
|
||||||
{
|
|
||||||
id: 24,
|
|
||||||
name: 'Custom Airplane',
|
|
||||||
model: 'twin_plane',
|
|
||||||
image: 'airplane',
|
|
||||||
enabled: false,
|
|
||||||
legacy: true,
|
|
||||||
platform: PLATFORM_AIRPLANE,
|
|
||||||
motorMixer: [],
|
|
||||||
servoMixer: []
|
|
||||||
}, // 24
|
|
||||||
{
|
{
|
||||||
id: 25,
|
id: 25,
|
||||||
name: 'Custom Tricopter',
|
name: 'Custom Tricopter',
|
||||||
|
@ -442,7 +328,67 @@ const mixerList = [
|
||||||
platform: PLATFORM_TRICOPTER,
|
platform: PLATFORM_TRICOPTER,
|
||||||
motorMixer: [],
|
motorMixer: [],
|
||||||
servoMixer: []
|
servoMixer: []
|
||||||
}, // 25
|
}, // 25
|
||||||
|
|
||||||
|
// ** Fixed Wing **
|
||||||
|
{
|
||||||
|
id: 8,
|
||||||
|
name: 'Flying Wing',
|
||||||
|
model: 'flying_wing',
|
||||||
|
image: 'flying_wing',
|
||||||
|
enabled: true,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorMixer: [
|
||||||
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
|
],
|
||||||
|
servoMixer: [
|
||||||
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
||||||
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
||||||
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
|
]
|
||||||
|
}, // 8
|
||||||
|
{
|
||||||
|
id: 27,
|
||||||
|
name: 'Flying Wing with differential thrust',
|
||||||
|
model: 'flying_wing',
|
||||||
|
image: 'flying_wing',
|
||||||
|
enabled: true,
|
||||||
|
legacy: false,
|
||||||
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorMixer: [
|
||||||
|
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
|
||||||
|
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
|
||||||
|
],
|
||||||
|
servoMixer: [
|
||||||
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
||||||
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
||||||
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
|
]
|
||||||
|
}, // 27
|
||||||
|
{
|
||||||
|
id: 14,
|
||||||
|
name: 'Airplane',
|
||||||
|
model: 'twin_plane',
|
||||||
|
image: 'airplane',
|
||||||
|
enabled: true,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
hasFlaps: true,
|
||||||
|
motorMixer: [
|
||||||
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
|
],
|
||||||
|
servoMixer: [
|
||||||
|
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
||||||
|
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
|
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
|
||||||
|
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
|
]
|
||||||
|
}, // 14
|
||||||
{
|
{
|
||||||
id: 26,
|
id: 26,
|
||||||
name: 'Airplane with differential thrust',
|
name: 'Airplane with differential thrust',
|
||||||
|
@ -464,10 +410,10 @@ const mixerList = [
|
||||||
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
|
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
|
||||||
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
]
|
]
|
||||||
},
|
}, // 26
|
||||||
{
|
{
|
||||||
id: 28,
|
id: 28,
|
||||||
name: 'Airplane V-tail (individual aileron servos)',
|
name: 'Airplane V-tail',
|
||||||
model: 'vtail_plane',
|
model: 'vtail_plane',
|
||||||
image: 'airplane_vtail',
|
image: 'airplane_vtail',
|
||||||
enabled: true,
|
enabled: true,
|
||||||
|
@ -487,7 +433,31 @@ const mixerList = [
|
||||||
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
|
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
|
||||||
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
|
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
|
||||||
]
|
]
|
||||||
},
|
}, // 28
|
||||||
|
{
|
||||||
|
id: 34,
|
||||||
|
name: 'Airplane V-tail with differential thrust',
|
||||||
|
model: 'vtail_plane',
|
||||||
|
image: 'airplane_vtail',
|
||||||
|
enabled: true,
|
||||||
|
legacy: false,
|
||||||
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
hasFlaps: true,
|
||||||
|
motorMixer: [
|
||||||
|
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
||||||
|
new MotorMixRule(1.0, 0.0, 0.0, -0.3)
|
||||||
|
],
|
||||||
|
servoMixer: [
|
||||||
|
new ServoMixRule(1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
|
new ServoMixRule(2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(2, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
|
new ServoMixRule(3, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
|
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
|
||||||
|
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
|
||||||
|
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
|
||||||
|
]
|
||||||
|
}, // 34
|
||||||
{
|
{
|
||||||
id: 29,
|
id: 29,
|
||||||
name: 'Airplane V-tail (single aileron servo)',
|
name: 'Airplane V-tail (single aileron servo)',
|
||||||
|
@ -506,7 +476,7 @@ const mixerList = [
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0),
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
|
||||||
]
|
]
|
||||||
},
|
}, //29
|
||||||
{
|
{
|
||||||
id: 30,
|
id: 30,
|
||||||
name: 'Airplane without rudder',
|
name: 'Airplane without rudder',
|
||||||
|
@ -526,7 +496,44 @@ const mixerList = [
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0),*/
|
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
]
|
]
|
||||||
},
|
}, // 30
|
||||||
|
{
|
||||||
|
id: 24,
|
||||||
|
name: 'Custom Airplane',
|
||||||
|
model: 'twin_plane',
|
||||||
|
image: 'airplane',
|
||||||
|
enabled: false,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
motorMixer: [],
|
||||||
|
servoMixer: []
|
||||||
|
}, // 24
|
||||||
|
|
||||||
|
// ** Helicopter **
|
||||||
|
{
|
||||||
|
id: 15,
|
||||||
|
name: 'Heli 120',
|
||||||
|
model: 'custom',
|
||||||
|
image: 'custom',
|
||||||
|
enabled: false,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_HELICOPTER,
|
||||||
|
motorMixer: [],
|
||||||
|
servoMixer: []
|
||||||
|
}, // 15
|
||||||
|
{
|
||||||
|
id: 16,
|
||||||
|
name: 'Heli 90',
|
||||||
|
model: 'custom',
|
||||||
|
image: 'custom',
|
||||||
|
enabled: false,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_HELICOPTER,
|
||||||
|
motorMixer: [],
|
||||||
|
servoMixer: []
|
||||||
|
}, // 16
|
||||||
|
|
||||||
|
// ** Other platforms **
|
||||||
{
|
{
|
||||||
id: 31,
|
id: 31,
|
||||||
name: 'Rover',
|
name: 'Rover',
|
||||||
|
@ -556,8 +563,8 @@ const mixerList = [
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
]
|
]
|
||||||
}
|
},
|
||||||
,
|
// ** Misc **
|
||||||
{
|
{
|
||||||
id: 33,
|
id: 33,
|
||||||
name: 'Other',
|
name: 'Other',
|
||||||
|
@ -572,7 +579,29 @@ const mixerList = [
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
]
|
]
|
||||||
}
|
},
|
||||||
|
{
|
||||||
|
id: 5,
|
||||||
|
name: 'Gimbal',
|
||||||
|
model: 'custom',
|
||||||
|
image: 'custom',
|
||||||
|
enabled: false,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_OTHER,
|
||||||
|
motorMixer: [],
|
||||||
|
servoMixer: []
|
||||||
|
}, // 5
|
||||||
|
{
|
||||||
|
id: 19,
|
||||||
|
name: 'PPM to SERVO',
|
||||||
|
model: 'custom',
|
||||||
|
image: 'custom',
|
||||||
|
enabled: false,
|
||||||
|
legacy: true,
|
||||||
|
platform: PLATFORM_OTHER,
|
||||||
|
motorMixer: [],
|
||||||
|
servoMixer: []
|
||||||
|
}, // 19
|
||||||
];
|
];
|
||||||
|
|
||||||
const platformList = [
|
const platformList = [
|
||||||
|
|
|
@ -7,9 +7,9 @@ var MotorMixRule = function (throttle, roll, pitch, yaw) {
|
||||||
|
|
||||||
self.fromMsp = function (mspThrottle, mspRoll, mspPitch, mspYaw) {
|
self.fromMsp = function (mspThrottle, mspRoll, mspPitch, mspYaw) {
|
||||||
throttle = mspThrottle / 1000;
|
throttle = mspThrottle / 1000;
|
||||||
roll = (mspRoll / 1000) - 2;
|
roll = Math.round(((mspRoll / 1000) - 2) * 1000) / 1000;
|
||||||
pitch = (mspPitch / 1000) - 2;
|
pitch = Math.round(((mspPitch / 1000) - 2) * 1000) / 1000;
|
||||||
yaw = (mspYaw / 1000) - 2;
|
yaw = Math.round(((mspYaw / 1000) - 2) * 1000) / 1000;
|
||||||
};
|
};
|
||||||
|
|
||||||
self.isUsed = function () {
|
self.isUsed = function () {
|
||||||
|
|
|
@ -99,5 +99,20 @@ let ServoMixerRuleCollection = function () {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
self.getNextUnusedIndex = function() {
|
||||||
|
let nextTarget = 0;
|
||||||
|
|
||||||
|
for (let ruleIndex in data) {
|
||||||
|
if (data.hasOwnProperty(ruleIndex)) {
|
||||||
|
let target = data[ruleIndex].getTarget();
|
||||||
|
if (target > nextTarget) {
|
||||||
|
nextTarget = target;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return nextTarget+1;
|
||||||
|
}
|
||||||
|
|
||||||
return self;
|
return self;
|
||||||
};
|
};
|
159
js/settings.js
159
js/settings.js
|
@ -1,5 +1,7 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
|
const GulpClient = require("gulp");
|
||||||
|
|
||||||
var Settings = (function () {
|
var Settings = (function () {
|
||||||
let self = {};
|
let self = {};
|
||||||
|
|
||||||
|
@ -38,6 +40,8 @@ var Settings = (function () {
|
||||||
}
|
}
|
||||||
parent.show();
|
parent.show();
|
||||||
|
|
||||||
|
input.prop('title', 'CLI: ' + input.data('setting'));
|
||||||
|
|
||||||
if (input.prop('tagName') == 'SELECT' || s.setting.table) {
|
if (input.prop('tagName') == 'SELECT' || s.setting.table) {
|
||||||
if (input.attr('type') == 'checkbox') {
|
if (input.attr('type') == 'checkbox') {
|
||||||
input.prop('checked', s.value > 0);
|
input.prop('checked', s.value > 0);
|
||||||
|
@ -79,9 +83,9 @@ var Settings = (function () {
|
||||||
input.val(s.value.toFixed(2));
|
input.val(s.value.toFixed(2));
|
||||||
} else {
|
} else {
|
||||||
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
||||||
input.attr('type', 'number');
|
|
||||||
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
|
|
||||||
|
|
||||||
|
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
|
||||||
|
input.attr('type', 'number');
|
||||||
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
|
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
|
||||||
input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier)));
|
input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier)));
|
||||||
}
|
}
|
||||||
|
@ -146,22 +150,39 @@ var Settings = (function () {
|
||||||
|
|
||||||
//display names for the units
|
//display names for the units
|
||||||
const unitDisplayDames = {
|
const unitDisplayDames = {
|
||||||
|
// Misc
|
||||||
'us' : "uS",
|
'us' : "uS",
|
||||||
'deg' : '°',
|
|
||||||
'cdeg' : 'centi°',
|
|
||||||
'cmss' : 'cm/s/s',
|
|
||||||
'cm' : 'cm',
|
|
||||||
'cms' : 'cm/s',
|
|
||||||
'm' : 'm',
|
|
||||||
'ms' : 'ms',
|
|
||||||
'mps' : 'm/s',
|
|
||||||
'kmh' : 'Km/h',
|
|
||||||
'sec' : 's',
|
|
||||||
'kt' : 'Kt',
|
|
||||||
'ft' : 'ft',
|
|
||||||
'mph' : 'mph',
|
|
||||||
'cw' : 'cW',
|
'cw' : 'cW',
|
||||||
'percent' : '%'
|
'percent' : '%',
|
||||||
|
'cmss' : 'cm/s/s',
|
||||||
|
// Time
|
||||||
|
'msec' : 'ms',
|
||||||
|
'dsec' : 'ds',
|
||||||
|
'sec' : 's',
|
||||||
|
// Angles
|
||||||
|
'deg' : '°',
|
||||||
|
'decideg' : 'deci°',
|
||||||
|
// Temperature
|
||||||
|
'decidegc' : 'deci°C',
|
||||||
|
'degc' : '°C',
|
||||||
|
'degf' : '°F',
|
||||||
|
// Speed
|
||||||
|
'cms' : 'cm/s',
|
||||||
|
'v-cms' : 'cm/s',
|
||||||
|
'ms' : 'm/s',
|
||||||
|
'kmh' : 'Km/h',
|
||||||
|
'mph' : 'mph',
|
||||||
|
'hftmin' : 'x100 ft/min',
|
||||||
|
'fts' : 'ft/s',
|
||||||
|
'kt' : 'Kt',
|
||||||
|
// Distance
|
||||||
|
'cm' : 'cm',
|
||||||
|
'm' : 'm',
|
||||||
|
'km' : 'Km',
|
||||||
|
'm-lrg' : 'm', // Metres, but converted to larger units
|
||||||
|
'ft' : 'ft',
|
||||||
|
'mi' : 'mi',
|
||||||
|
'nm' : 'NM'
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -179,51 +200,97 @@ var Settings = (function () {
|
||||||
'm' : 100,
|
'm' : 100,
|
||||||
'ft' : 30.48
|
'ft' : 30.48
|
||||||
},
|
},
|
||||||
'cms' : {
|
'm' : {
|
||||||
|
'm' : 1,
|
||||||
|
'ft' : 0.3048
|
||||||
|
},
|
||||||
|
'm-lrg' : {
|
||||||
|
'km' : 1000,
|
||||||
|
'mi' : 1609.344,
|
||||||
|
'nm' : 1852
|
||||||
|
},
|
||||||
|
'cms' : { // Horizontal speed
|
||||||
'kmh' : 27.77777777777778,
|
'kmh' : 27.77777777777778,
|
||||||
'kt': 51.44444444444457,
|
'kt': 51.44444444444457,
|
||||||
'mph' : 44.704,
|
'mph' : 44.704,
|
||||||
'mps' : 100
|
'ms' : 100
|
||||||
},
|
},
|
||||||
'ms' : {
|
'v-cms' : { // Vertical speed
|
||||||
|
'ms' : 100,
|
||||||
|
'hftmin' : 50.8,
|
||||||
|
'fts' : 30.48
|
||||||
|
},
|
||||||
|
'msec' : {
|
||||||
'sec' : 1000
|
'sec' : 1000
|
||||||
},
|
},
|
||||||
'cdeg' : {
|
'dsec' : {
|
||||||
|
'sec' : 10
|
||||||
|
},
|
||||||
|
'decideg' : {
|
||||||
'deg' : 10
|
'deg' : 10
|
||||||
},
|
},
|
||||||
|
'decidegc' : {
|
||||||
|
'degc' : 10,
|
||||||
|
'degf' : 'FAHREN'
|
||||||
|
},
|
||||||
};
|
};
|
||||||
|
|
||||||
//this holds which units get converted in which unit systems
|
//this holds which units get converted in which unit systems
|
||||||
const conversionTable = {
|
const conversionTable = {
|
||||||
0: { //imperial
|
0: { //imperial
|
||||||
'cm' : 'ft',
|
'cm' : 'ft',
|
||||||
|
'm' : 'ft',
|
||||||
|
'm-lrg' : 'mi',
|
||||||
'cms' : 'mph',
|
'cms' : 'mph',
|
||||||
'cdeg' : 'deg',
|
'v-cms' : 'fts',
|
||||||
'ms' : 'sec'
|
'msec' : 'sec',
|
||||||
|
'dsec' : 'sec',
|
||||||
|
'decideg' : 'deg',
|
||||||
|
'decidegc' : 'degf',
|
||||||
},
|
},
|
||||||
1: {//metric
|
1: { //metric
|
||||||
'cm': 'm',
|
'cm': 'm',
|
||||||
|
'm' : 'm',
|
||||||
|
'm-lrg' : 'km',
|
||||||
'cms' : 'kmh',
|
'cms' : 'kmh',
|
||||||
'ms' : 'sec',
|
'v-cms' : 'ms',
|
||||||
'cdeg' : 'deg'
|
'msec' : 'sec',
|
||||||
|
'dsec' : 'sec',
|
||||||
|
'decideg' : 'deg',
|
||||||
|
'decidegc' : 'degc',
|
||||||
},
|
},
|
||||||
2: { //metric with MPH
|
2: { //metric with MPH
|
||||||
'cm': 'm',
|
'cm': 'm',
|
||||||
|
'm' : 'm',
|
||||||
|
'm-lrg' : 'km',
|
||||||
'cms' : 'mph',
|
'cms' : 'mph',
|
||||||
'cdeg' : 'deg',
|
'v-cms' : 'ms',
|
||||||
'ms' : 'sec'
|
'decideg' : 'deg',
|
||||||
|
'msec' : 'sec',
|
||||||
|
'dsec' : 'sec',
|
||||||
|
'decidegc' : 'degc',
|
||||||
},
|
},
|
||||||
3:{ //UK
|
3:{ //UK
|
||||||
'cm' : 'ft',
|
'cm' : 'ft',
|
||||||
|
'm' : 'ft',
|
||||||
|
'm-lrg' : 'mi',
|
||||||
'cms' : 'mph',
|
'cms' : 'mph',
|
||||||
'cdeg' : 'deg',
|
'v-cms' : 'fts',
|
||||||
'ms' : 'sec'
|
'decideg' : 'deg',
|
||||||
|
'msec' : 'sec',
|
||||||
|
'dsec' : 'sec',
|
||||||
|
'decidegc' : 'degc',
|
||||||
},
|
},
|
||||||
4: { //General aviation
|
4: { //General aviation
|
||||||
'cm' : 'ft',
|
'cm' : 'ft',
|
||||||
|
'm' : 'ft',
|
||||||
|
'm-lrg' : 'nm',
|
||||||
'cms': 'kt',
|
'cms': 'kt',
|
||||||
'cdeg' : 'deg',
|
'v-cms' : 'hftmin',
|
||||||
'ms' : 'sec'
|
'decideg' : 'deg',
|
||||||
|
'msec' : 'sec',
|
||||||
|
'dsec' : 'sec',
|
||||||
|
'decidegc' : 'degc',
|
||||||
},
|
},
|
||||||
default:{}//show base units
|
default:{}//show base units
|
||||||
};
|
};
|
||||||
|
@ -249,18 +316,31 @@ var Settings = (function () {
|
||||||
// Update the step, min, and max; as we have the multiplier here.
|
// Update the step, min, and max; as we have the multiplier here.
|
||||||
if (element.attr('type') == 'number') {
|
if (element.attr('type') == 'number') {
|
||||||
element.attr('step', ((multiplier != 1) ? '0.01' : '1'));
|
element.attr('step', ((multiplier != 1) ? '0.01' : '1'));
|
||||||
element.attr('min', (element.attr('min') / multiplier).toFixed(2));
|
if (multiplier != 'FAHREN') {
|
||||||
element.attr('max', (element.attr('max') / multiplier).toFixed(2));
|
element.attr('min', (element.attr('min') / multiplier).toFixed(2));
|
||||||
|
element.attr('max', (element.attr('max') / multiplier).toFixed(2));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update the input with a new formatted unit
|
// Update the input with a new formatted unit
|
||||||
const convertedValue = Number((oldValue / multiplier).toFixed(2));
|
let newValue = "";
|
||||||
const newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
|
if (multiplier == 'FAHREN') {
|
||||||
|
element.attr('min', toFahrenheit(element.attr('min')).toFixed(2));
|
||||||
|
element.attr('max', toFahrenheit(element.attr('max')).toFixed(2));
|
||||||
|
newValue = toFahrenheit(oldValue).toFixed(2);
|
||||||
|
} else {
|
||||||
|
const convertedValue = Number((oldValue / multiplier).toFixed(2));
|
||||||
|
newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
|
||||||
|
}
|
||||||
element.val(newValue);
|
element.val(newValue);
|
||||||
element.data('setting-multiplier', multiplier);
|
element.data('setting-multiplier', multiplier);
|
||||||
|
|
||||||
// Now wrap the input in a display that shows the unit
|
// Now wrap the input in a display that shows the unit
|
||||||
element.wrap(`<div data-unit="${unitDisplayDames[unitName]}" class="unit_wrapper unit"></div>`);
|
element.wrap(`<div data-unit="${unitDisplayDames[unitName]}" class="unit_wrapper unit"></div>`);
|
||||||
|
|
||||||
|
function toFahrenheit(decidegC) {
|
||||||
|
return (decidegC / 10) * 1.8 + 32;
|
||||||
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
self.saveInput = function(input) {
|
self.saveInput = function(input) {
|
||||||
|
@ -281,8 +361,13 @@ var Settings = (function () {
|
||||||
} else if(setting.type == 'string') {
|
} else if(setting.type == 'string') {
|
||||||
value = input.val();
|
value = input.val();
|
||||||
} else {
|
} else {
|
||||||
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
var multiplier = input.data('setting-multiplier') || 1;
|
||||||
value = parseFloat(input.val()) * multiplier;
|
if (multiplier == 'FAHREN') {
|
||||||
|
value = Math.round(((parseFloat(input.val())-32) / 1.8) * 10);
|
||||||
|
} else {
|
||||||
|
multiplier = parseFloat(multiplier);
|
||||||
|
value = Math.round(parseFloat(input.val()) * multiplier);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return mspHelper.setSetting(settingName, value);
|
return mspHelper.setSetting(settingName, value);
|
||||||
};
|
};
|
||||||
|
|
14
main.css
14
main.css
|
@ -2221,11 +2221,19 @@ ol li {
|
||||||
position: relative;
|
position: relative;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.unit_wrapper input {
|
||||||
|
margin-right: 0 !important;
|
||||||
|
}
|
||||||
|
|
||||||
|
.unit_wrapper ~ label, select ~ label, input ~ label {
|
||||||
|
margin-left: 10px;
|
||||||
|
}
|
||||||
|
|
||||||
/* Position the unit to the right of the wrapper */
|
/* Position the unit to the right of the wrapper */
|
||||||
.unit_wrapper::after {
|
.unit_wrapper::after {
|
||||||
position: absolute;
|
position: absolute;
|
||||||
top: 2px;
|
top: 2px;
|
||||||
right: .7em;
|
right: .5em;
|
||||||
transition: all .05s ease-in-out;
|
transition: all .05s ease-in-out;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2233,13 +2241,13 @@ ol li {
|
||||||
for arrow buttons will appear to the right of number inputs */
|
for arrow buttons will appear to the right of number inputs */
|
||||||
.unit_wrapper:hover::after,
|
.unit_wrapper:hover::after,
|
||||||
.unit_wrapper:focus-within::after {
|
.unit_wrapper:focus-within::after {
|
||||||
right: 1.3em;
|
right: 1.0em;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Handle Firefox (arrows always shown) */
|
/* Handle Firefox (arrows always shown) */
|
||||||
@supports (-moz-appearance:none) {
|
@supports (-moz-appearance:none) {
|
||||||
.unit_wrapper::after {
|
.unit_wrapper::after {
|
||||||
right: 1.3em;
|
right: 1.0em;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -28,12 +28,12 @@
|
||||||
text-align: left;
|
text-align: left;
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
margin-right: 11px;
|
|
||||||
font-size: 12px;
|
font-size: 12px;
|
||||||
font-weight: normal;
|
font-weight: normal;
|
||||||
}
|
}
|
||||||
|
|
||||||
.config-section .number input,
|
.config-section .number input,
|
||||||
|
.config-section .checkbox input,
|
||||||
.tab-configuration .number input {
|
.tab-configuration .number input {
|
||||||
width: 106px;
|
width: 106px;
|
||||||
}
|
}
|
||||||
|
@ -221,7 +221,7 @@ hr {
|
||||||
|
|
||||||
.config-section label {
|
.config-section label {
|
||||||
position: absolute;
|
position: absolute;
|
||||||
left: 118px;
|
left: 108px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.config-section .radio label {
|
.config-section .radio label {
|
||||||
|
|
|
@ -26,7 +26,6 @@
|
||||||
text-align: left;
|
text-align: left;
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
margin-right: 11px;
|
|
||||||
font-size: 12px;
|
font-size: 12px;
|
||||||
font-weight: normal;
|
font-weight: normal;
|
||||||
}
|
}
|
||||||
|
@ -253,10 +252,12 @@
|
||||||
height: 90px;
|
height: 90px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-failsafe .minimumDistance {
|
.tab-failsafe input {
|
||||||
width: 100px !important;
|
width: 75px !important;
|
||||||
padding-left: 3px;
|
}
|
||||||
margin-right: 11px;
|
|
||||||
|
.tab-failsafe select {
|
||||||
|
width: 79px;
|
||||||
}
|
}
|
||||||
|
|
||||||
@media only screen and (max-width: 1055px) , only screen and (max-device-width: 1055px) {
|
@media only screen and (max-width: 1055px) , only screen and (max-device-width: 1055px) {
|
||||||
|
|
|
@ -271,7 +271,6 @@
|
||||||
text-align: left;
|
text-align: left;
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
margin-right: 11px;
|
|
||||||
margin-bottom: 5px;
|
margin-bottom: 5px;
|
||||||
font-size: 12px;
|
font-size: 12px;
|
||||||
font-weight: normal;
|
font-weight: normal;
|
||||||
|
|
|
@ -477,21 +477,19 @@ button {
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-osd .settings input {
|
.tab-osd .settings input {
|
||||||
width: 55px;
|
width: 75px;
|
||||||
padding-left: 3px;
|
padding-left: 3px;
|
||||||
height: 18px;
|
height: 18px;
|
||||||
line-height: 20px;
|
line-height: 20px;
|
||||||
text-align: left;
|
text-align: left;
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
margin-right: 11px;
|
|
||||||
font-size: 11px;
|
font-size: 11px;
|
||||||
font-weight: normal;
|
font-weight: normal;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-osd .settings select {
|
.tab-osd .settings select {
|
||||||
width: 75px;
|
width: 75px;
|
||||||
margin-right: 11px;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-osd .settings .switchery {
|
.tab-osd .settings .switchery {
|
||||||
|
|
|
@ -302,7 +302,6 @@
|
||||||
text-align: left;
|
text-align: left;
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
margin-right: 11px;
|
|
||||||
font-weight: normal;
|
font-weight: normal;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -12,7 +12,6 @@
|
||||||
text-align: left;
|
text-align: left;
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
margin-right: 11px;
|
|
||||||
font-size: 12px;
|
font-size: 12px;
|
||||||
font-weight: normal;
|
font-weight: normal;
|
||||||
}
|
}
|
||||||
|
|
|
@ -149,7 +149,7 @@
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="pitchToThrottleThreshold" type="number" data-unit="cdeg" data-setting="nav_fw_pitch2thr_threshold" data-setting-multiplier="1" step="1" min="0" max="900" />
|
<input id="pitchToThrottleThreshold" type="number" data-unit="decideg" data-setting="nav_fw_pitch2thr_threshold" data-setting-multiplier="1" step="1" min="0" max="900" />
|
||||||
<label for="pitchToThrottleThreshold"><span data-i18n="pitchToThrottleThreshold"></span></label>
|
<label for="pitchToThrottleThreshold"><span data-i18n="pitchToThrottleThreshold"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleThresholdHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="pitchToThrottleThresholdHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -393,13 +393,13 @@
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="navManualClimbRate" data-unit="cms" data-setting="nav_manual_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
<input type="number" id="navManualClimbRate" data-unit="v-cms" data-setting="nav_manual_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
<label for="navManualClimbRate"><span data-i18n="navManualClimbRate"></span></label>
|
<label for="navManualClimbRate"><span data-i18n="navManualClimbRate"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="navManualClimbRateHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="navManualClimbRateHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="navAutoClimbRate" data-unit="cms" data-setting="nav_auto_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
<input type="number" id="navAutoClimbRate" data-unit="v-cms" data-setting="nav_auto_climb_rate" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
<label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
|
<label for="navAutoClimbRate"><span data-i18n="navAutoClimbRate"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="navAutoClimbRateHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -427,14 +427,14 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="config-setion gui_box grey">
|
<div class="config-section gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" data-i18n="autoLandingSettings"></div>
|
<div class="spacer_box_title" data-i18n="autoLandingSettings"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="landMaxAltVspd" type="number" data-unit="cms" data-setting="nav_land_maxalt_vspd" data-setting-multiplier="1" step="1" min="100" max="2000" />
|
<input id="landMaxAltVspd" type="number" data-unit="v-cms" data-setting="nav_land_maxalt_vspd" data-setting-multiplier="1" step="1" min="100" max="2000" />
|
||||||
<label for="landMaxAltVspd"><span data-i18n="landMaxAltVspd"></span></label>
|
<label for="landMaxAltVspd"><span data-i18n="landMaxAltVspd"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="landMaxAltVspdHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="landMaxAltVspdHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -446,7 +446,7 @@
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="landMinAltVspd" type="number" data-unit="cms" data-setting="nav_land_minalt_vspd" data-setting-multiplier="1" step="1" min="50" max="500" />
|
<input id="landMinAltVspd" type="number" data-unit="v-cms" data-setting="nav_land_minalt_vspd" data-setting-multiplier="1" step="1" min="50" max="500" />
|
||||||
<label for="landMinAltVspd"><span data-i18n="landMinAltVspd"></span></label>
|
<label for="landMinAltVspd"><span data-i18n="landMinAltVspd"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="landMinAltVspdHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="landMinAltVspdHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -7,9 +7,8 @@
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<label> <input type="number" name="failsafe_delay" min="0" max="200" /> <span
|
<input type="number" name="failsafe_delay" data-unit="dsec" data-setting="failsafe_delay" min="0" max="200" />
|
||||||
data-i18n="failsafeDelayItem"></span>
|
<label><span data-i18n="failsafeDelayItem"></span></label>
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="failsafeDelayHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="failsafeDelayHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<!-- radio buttons -->
|
<!-- radio buttons -->
|
||||||
|
@ -25,14 +24,12 @@
|
||||||
</div>
|
</div>
|
||||||
<div class="proceduresettings">
|
<div class="proceduresettings">
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<label> <input type="number" name="failsafe_throttle" min="0" max="2000" /> <span
|
<input type="number" name="failsafe_throttle" data-setting="failsafe_throttle" data-unit="us" min="0" max="2000" />
|
||||||
data-i18n="failsafeThrottleItem"></span>
|
<label><span data-i18n="failsafeThrottleItem"></span></label>
|
||||||
</label>
|
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<label> <input type="number" name="failsafe_off_delay" min="0" max="200" /> <span
|
<input type="number" name="failsafe_off_delay" data-setting="failsafe_off_delay" data-unit="dsec" min="0" max="200" />
|
||||||
data-i18n="failsafeOffDelayItem"></span>
|
<label><span data-i18n="failsafeOffDelayItem"></span></label>
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="failsafeOffDelayHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="failsafeOffDelayHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -58,14 +55,13 @@
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number" id="failsafe_min_distance_elements">
|
<div class="number" id="failsafe_min_distance_elements">
|
||||||
<label> <input class="minimumDistance" type="number" name="failsafe_min_distance" id="failsafe_min_distance" min="0" max="65000" /> <span
|
<input class="minimumDistance" id="failsafe_min_distance" type="number" data-unit="cm" data-setting="failsafe_min_distance" data-setting-multiplier="1" step="1" min="0" max="65000" />
|
||||||
data-i18n="failsafeMinDistanceItem"></span>
|
<label for="failsafe_min_distance"><span data-i18n="failsafeMinDistanceItem"></span></label>
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="failsafeMinDistanceHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="failsafeMinDistanceHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="select" id="failsafe_min_distance_procedure_elements">
|
<div class="select" id="failsafe_min_distance_procedure_elements">
|
||||||
<select class="minimumDistance" id="failsafe_min_distance_procedure"></select>
|
<select id="failsafe_min_distance_procedure" class="minimumDistance" data-setting="failsafe_min_distance_procedure"></select>
|
||||||
<label for="failsafe_min_distance_procedure"> <span data-i18n="failsafeMinDistanceProcedureItem"></span></label>
|
<label for="failsafe_min_distance_procedure"> <span data-i18n="failsafeMinDistanceProcedureItem"></span></label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="failsafeMinDistanceProcedureHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="failsafeMinDistanceProcedureHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
218
tabs/failsafe.js
218
tabs/failsafe.js
|
@ -9,42 +9,154 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
googleAnalytics.sendAppView('Failsafe');
|
googleAnalytics.sendAppView('Failsafe');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Can get rid of this when MSPHelper supports strings (fixed in #7734, awaiting merge)
|
||||||
function load_failssafe_config() {
|
function load_failssafe_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_config);
|
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_config() {
|
/* function load_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
|
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_misc() {
|
function load_misc() {
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
|
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
|
||||||
}
|
}*/
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
GUI.load("./tabs/failsafe.html", process_html);
|
GUI.load("./tabs/failsafe.html", Settings.processHtml(function() {
|
||||||
|
GUI.simpleBind();
|
||||||
|
|
||||||
|
// translate to user-selected language
|
||||||
|
localize();
|
||||||
|
|
||||||
|
// for some odd reason chrome 38+ changes scroll according to the touched select element
|
||||||
|
// i am guessing this is a bug, since this wasn't happening on 37
|
||||||
|
// code below is a temporary fix, which we will be able to remove in the future (hopefully)
|
||||||
|
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
||||||
|
|
||||||
|
// set stage 2 failsafe procedure
|
||||||
|
$('input[type="radio"].procedure').change(function () {
|
||||||
|
var element = $(this),
|
||||||
|
checked = element.is(':checked'),
|
||||||
|
id = element.attr('id');
|
||||||
|
switch (id) {
|
||||||
|
case 'drop':
|
||||||
|
if (checked) {
|
||||||
|
$('input[name="failsafe_throttle"]').prop("disabled", true);
|
||||||
|
$('input[name="failsafe_off_delay"]').prop("disabled", true);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 'land':
|
||||||
|
if (checked) {
|
||||||
|
$('input[name="failsafe_throttle"]').prop("disabled", false);
|
||||||
|
$('input[name="failsafe_off_delay"]').prop("disabled", false);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
// switch (MSPHelper.getSetting('failsafe_procedure')) { // Use once #7734 is merged
|
||||||
|
switch (FAILSAFE_CONFIG.failsafe_procedure) {
|
||||||
|
default:
|
||||||
|
case 0:
|
||||||
|
element = $('input[id="land"]');
|
||||||
|
element.prop('checked', true);
|
||||||
|
element.change();
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
element = $('input[id="drop"]');
|
||||||
|
element.prop('checked', true);
|
||||||
|
element.change();
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
element = $('input[id="rth"]');
|
||||||
|
element.prop('checked', true);
|
||||||
|
element.change();
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
element = $('input[id="nothing"]');
|
||||||
|
element.prop('checked', true);
|
||||||
|
element.change();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Adjust Minimum Distance values when checkbox is checked/unchecked
|
||||||
|
$('#failsafe_use_minimum_distance').change(function() {
|
||||||
|
if ($(this).is(':checked')) {
|
||||||
|
// No default distance added due to conversions
|
||||||
|
$('#failsafe_min_distance_elements').show();
|
||||||
|
$('#failsafe_min_distance_procedure_elements').show();
|
||||||
|
} else {
|
||||||
|
// If they uncheck it, clear the distance to 0, which disables this feature
|
||||||
|
$('#failsafe_min_distance').val(0);
|
||||||
|
$('#failsafe_min_distance_elements').hide();
|
||||||
|
$('#failsafe_min_distance_procedure_elements').hide();
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
// Set initial state of controls according to data
|
||||||
|
if ( $('#failsafe_min_distance').val() > 0) {
|
||||||
|
$('#failsafe_use_minimum_distance').prop('checked', true);
|
||||||
|
$('#failsafe_min_distance_elements').show();
|
||||||
|
$('#failsafe_min_distance_procedure_elements').show();
|
||||||
|
} else {
|
||||||
|
$('#failsafe_use_minimum_distance').prop('checked', false);
|
||||||
|
$('#failsafe_min_distance_elements').hide();
|
||||||
|
$('#failsafe_min_distance_procedure_elements').hide();
|
||||||
|
}
|
||||||
|
|
||||||
|
$('a.save').click(function () {
|
||||||
|
if ($('input[id="land"]').is(':checked')) {
|
||||||
|
FAILSAFE_CONFIG.failsafe_procedure = 0;
|
||||||
|
} else if ($('input[id="drop"]').is(':checked')) {
|
||||||
|
FAILSAFE_CONFIG.failsafe_procedure = 1;
|
||||||
|
} else if ($('input[id="rth"]').is(':checked')) {
|
||||||
|
FAILSAFE_CONFIG.failsafe_procedure = 2;
|
||||||
|
} else if ($('input[id="nothing"]').is(':checked')) {
|
||||||
|
FAILSAFE_CONFIG.failsafe_procedure = 3;
|
||||||
|
}
|
||||||
|
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, savePhaseTwo);
|
||||||
|
});
|
||||||
|
|
||||||
|
GUI.content_ready(callback);
|
||||||
|
}));
|
||||||
}
|
}
|
||||||
|
|
||||||
load_failssafe_config();
|
load_failssafe_config();
|
||||||
|
|
||||||
function process_html() {
|
function savePhaseTwo() {
|
||||||
|
Settings.saveInputs().then(function () {
|
||||||
|
var self = this;
|
||||||
|
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||||
|
setTimeout(function () {
|
||||||
|
$(self).html(oldText);
|
||||||
|
}, 2000);
|
||||||
|
reboot();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
// translate to user-selected language
|
function reboot() {
|
||||||
localize();
|
//noinspection JSUnresolvedVariable
|
||||||
|
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||||
|
GUI.tab_switch_cleanup(function () {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
var $failsafeUseMinimumDistanceCheckbox = $('#failsafe_use_minimum_distance');
|
function reinitialize() {
|
||||||
var $failsafeMinDistanceElements = $('#failsafe_min_distance_elements')
|
//noinspection JSUnresolvedVariable
|
||||||
var $failsafeMinDistance = $('#failsafe_min_distance')
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
var $failsafeMinDistanceProcedureElements = $('#failsafe_min_distance_procedure_elements')
|
GUI.handleReconnect($('.tab_failsafe a'));
|
||||||
var $failsafeMinDistanceProcedure = $('#failsafe_min_distance_procedure');
|
}
|
||||||
|
|
||||||
|
/*function process_html() {
|
||||||
|
|
||||||
// generate labels for assigned aux modes
|
// generate labels for assigned aux modes
|
||||||
var element;
|
var element;
|
||||||
|
|
||||||
// for some odd reason chrome 38+ changes scroll according to the touched select element
|
|
||||||
// i am guessing this is a bug, since this wasn't happening on 37
|
|
||||||
// code below is a temporary fix, which we will be able to remove in the future (hopefully)
|
|
||||||
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
|
||||||
|
|
||||||
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
|
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
|
||||||
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
||||||
|
@ -52,77 +164,11 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
|
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
|
||||||
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
|
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
|
||||||
|
|
||||||
// set stage 2 failsafe procedure
|
|
||||||
$('input[type="radio"].procedure').change(function () {
|
|
||||||
var element = $(this),
|
|
||||||
checked = element.is(':checked'),
|
|
||||||
id = element.attr('id');
|
|
||||||
switch (id) {
|
|
||||||
case 'drop':
|
|
||||||
if (checked) {
|
|
||||||
$('input[name="failsafe_throttle"]').prop("disabled", true);
|
|
||||||
$('input[name="failsafe_off_delay"]').prop("disabled", true);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'land':
|
|
||||||
if (checked) {
|
|
||||||
$('input[name="failsafe_throttle"]').prop("disabled", false);
|
|
||||||
$('input[name="failsafe_off_delay"]').prop("disabled", false);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
switch (FAILSAFE_CONFIG.failsafe_procedure) {
|
|
||||||
default:
|
|
||||||
case 0:
|
|
||||||
element = $('input[id="land"]');
|
|
||||||
element.prop('checked', true);
|
|
||||||
element.change();
|
|
||||||
break;
|
|
||||||
case 1:
|
|
||||||
element = $('input[id="drop"]');
|
|
||||||
element.prop('checked', true);
|
|
||||||
element.change();
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
element = $('input[id="rth"]');
|
|
||||||
element.prop('checked', true);
|
|
||||||
element.change();
|
|
||||||
break;
|
|
||||||
case 3:
|
|
||||||
element = $('input[id="nothing"]');
|
|
||||||
element.prop('checked', true);
|
|
||||||
element.change();
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Adjust Minimum Distance values when checkbox is checked/unchecked
|
|
||||||
$failsafeUseMinimumDistanceCheckbox.change(function() {
|
|
||||||
if ($(this).is(':checked')) {
|
|
||||||
// 20 meters seems like a reasonable default for a minimum distance
|
|
||||||
$failsafeMinDistance.val(2000);
|
|
||||||
$failsafeMinDistanceElements.show();
|
|
||||||
$failsafeMinDistanceProcedureElements.show();
|
|
||||||
} else {
|
|
||||||
// If they uncheck it, clear the distance to 0, which disables this feature
|
|
||||||
$failsafeMinDistance.val(0);
|
|
||||||
$failsafeMinDistanceElements.hide();
|
|
||||||
$failsafeMinDistanceProcedureElements.hide();
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
// Set initial state of controls according to data
|
|
||||||
if (FAILSAFE_CONFIG.failsafe_min_distance > 0) {
|
|
||||||
$failsafeUseMinimumDistanceCheckbox.prop('checked', true);
|
|
||||||
$failsafeMinDistanceElements.show();
|
|
||||||
$failsafeMinDistanceProcedureElements.show();
|
|
||||||
} else {
|
|
||||||
$failsafeUseMinimumDistanceCheckbox.prop('checked', false);
|
|
||||||
$failsafeMinDistanceElements.hide();
|
|
||||||
$failsafeMinDistanceProcedureElements.hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Alternate, minimum distance failsafe procedure
|
// Alternate, minimum distance failsafe procedure
|
||||||
GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
||||||
|
@ -177,7 +223,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
});
|
});
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
}
|
}*/
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.failsafe.cleanup = function (callback) {
|
TABS.failsafe.cleanup = function (callback) {
|
||||||
|
|
|
@ -438,7 +438,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
$("[data-role='role-servo-add']").click(function () {
|
$("[data-role='role-servo-add']").click(function () {
|
||||||
if (SERVO_RULES.hasFreeSlots()) {
|
if (SERVO_RULES.hasFreeSlots()) {
|
||||||
SERVO_RULES.put(new ServoMixRule(0, 0, 100, 0));
|
SERVO_RULES.put(new ServoMixRule(SERVO_RULES.getNextUnusedIndex(), 0, 100, 0));
|
||||||
renderServoMixRules();
|
renderServoMixRules();
|
||||||
renderOutputMapping();
|
renderOutputMapping();
|
||||||
}
|
}
|
||||||
|
|
|
@ -123,17 +123,17 @@
|
||||||
<span data-i18n="osd_time_alarm"></span>
|
<span data-i18n="osd_time_alarm"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="osd_alt_alarm">
|
<label for="osd_alt_alarm">
|
||||||
<input id="osd_alt_alarm" data-setting="osd_alt_alarm" data-setting-multiplier="1" type="number" data-step="1" />
|
<input id="osd_alt_alarm" data-setting="osd_alt_alarm" data-unit="m" data-setting-multiplier="1" type="number" data-step="1" />
|
||||||
<span data-i18n="osd_alt_alarm"></span>
|
<span data-i18n="osd_alt_alarm"></span>
|
||||||
</label>
|
</label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="osdAlarmMAX_NEG_ALTITUDE_HELP"></div>
|
<div class="helpicon cf_tip" data-i18n_title="osdAlarmMAX_NEG_ALTITUDE_HELP"></div>
|
||||||
<label for="osd_neg_alt_alarm">
|
<label for="osd_neg_alt_alarm">
|
||||||
<input id="osd_neg_alt_alarm" data-setting="osd_neg_alt_alarm" data-setting-multiplier="1" type="number" data-step="1" />
|
<input id="osd_neg_alt_alarm" data-setting="osd_neg_alt_alarm" data-unit="m" data-setting-multiplier="1" type="number" data-step="1" />
|
||||||
<span data-i18n="osd_neg_alt_alarm"></span>
|
<span data-i18n="osd_neg_alt_alarm"></span>
|
||||||
</label>
|
</label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="osdAlarmDIST_HELP"></div>
|
<div class="helpicon cf_tip" data-i18n_title="osdAlarmDIST_HELP"></div>
|
||||||
<label for="osd_dist_alarm">
|
<label for="osd_dist_alarm">
|
||||||
<input id="osd_dist_alarm" data-setting="osd_dist_alarm" data-setting-multiplier="1" type="number" data-step="1" />
|
<input id="osd_dist_alarm" data-setting="osd_dist_alarm" data-unit="m-lrg" data-setting-multiplier="1" type="number" data-step="1" />
|
||||||
<span data-i18n="osd_dist_alarm"></span>
|
<span data-i18n="osd_dist_alarm"></span>
|
||||||
</label>
|
</label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="osdAlarmGFORCE_HELP"></div>
|
<div class="helpicon cf_tip" data-i18n_title="osdAlarmGFORCE_HELP"></div>
|
||||||
|
@ -157,27 +157,27 @@
|
||||||
<span data-i18n="osd_current_alarm"></span>
|
<span data-i18n="osd_current_alarm"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="imu_temp_alarm_min">
|
<label for="imu_temp_alarm_min">
|
||||||
<input id="imu_temp_alarm_min" data-setting="osd_imu_temp_alarm_min" data-setting-multiplier="10" type="number" data-step="0.5" />
|
<input id="imu_temp_alarm_min" data-setting="osd_imu_temp_alarm_min" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
|
||||||
<span data-i18n="osd_imu_temp_alarm_min"></span>
|
<span data-i18n="osd_imu_temp_alarm_min"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="imu_temp_alarm_max">
|
<label for="imu_temp_alarm_max">
|
||||||
<input id="imu_temp_alarm_max" data-setting="osd_imu_temp_alarm_max" data-setting-multiplier="10" type="number" data-step="0.5" />
|
<input id="imu_temp_alarm_max" data-setting="osd_imu_temp_alarm_max" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
|
||||||
<span data-i18n="osd_imu_temp_alarm_max"></span>
|
<span data-i18n="osd_imu_temp_alarm_max"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="baro_temp_alarm_min">
|
<label for="baro_temp_alarm_min">
|
||||||
<input id="baro_temp_alarm_min" data-setting="osd_baro_temp_alarm_min" data-setting-multiplier="10" type="number" data-step="0.5" />
|
<input id="baro_temp_alarm_min" data-setting="osd_baro_temp_alarm_min" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
|
||||||
<span data-i18n="osd_baro_temp_alarm_min"></span>
|
<span data-i18n="osd_baro_temp_alarm_min"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="baro_temp_alarm_max">
|
<label for="baro_temp_alarm_max">
|
||||||
<input id="baro_temp_alarm_max" data-setting="osd_baro_temp_alarm_max" data-setting-multiplier="10" type="number" data-step="0.5" />
|
<input id="baro_temp_alarm_max" data-setting="osd_baro_temp_alarm_max" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
|
||||||
<span data-i18n="osd_baro_temp_alarm_max"></span>
|
<span data-i18n="osd_baro_temp_alarm_max"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="esc_temp_alarm_min">
|
<label for="esc_temp_alarm_min">
|
||||||
<input id="esc_temp_alarm_min" data-setting="osd_esc_temp_alarm_min" data-setting-multiplier="10" type="number" data-step="0.5" />
|
<input id="esc_temp_alarm_min" data-setting="osd_esc_temp_alarm_min" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
|
||||||
<span data-i18n="osd_esc_temp_alarm_min"></span>
|
<span data-i18n="osd_esc_temp_alarm_min"></span>
|
||||||
</label>
|
</label>
|
||||||
<label for="esc_temp_alarm_max">
|
<label for="esc_temp_alarm_max">
|
||||||
<input id="esc_temp_alarm_max" data-setting="osd_esc_temp_alarm_max" data-setting-multiplier="10" type="number" data-step="0.5" />
|
<input id="esc_temp_alarm_max" data-setting="osd_esc_temp_alarm_max" data-unit="decidegc" data-setting-multiplier="1" type="number" data-step="0.5" />
|
||||||
<span data-i18n="osd_esc_temp_alarm_max"></span>
|
<span data-i18n="osd_esc_temp_alarm_max"></span>
|
||||||
</label>
|
</label>
|
||||||
<div class="helpicon cf_tip" data-i18n_title="osdalarmLQ_HELP"></div>
|
<div class="helpicon cf_tip" data-i18n_title="osdalarmLQ_HELP"></div>
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue