mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge remote-tracking branch 'origin/rel-15.02' into next
Conflicts: ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h
This commit is contained in:
commit
12a81827f8
@ -1,4 +1,4 @@
|
||||
--- RELEASE-15.02 RC4
|
||||
--- RELEASE-15.02 RC6
|
||||
This release introduces major flight performance improvements, enhancements as well as bug fixes. Many enhancements have been made to reducing dead-time of the communication between the flight controller and ESCs. In our testing, we have found this to be not only the best flight performance so far in the OpenPilot project but the best flight performance of any project we have tested against. This is a recommended upgrade for everyone and the more skilled of a pilot you are, the more you will love this release.
|
||||
|
||||
A key improvement that helped achieve this was the addition of the PWMSync code path, this is now enabled by default. Some restrictions applies to CC3D/CC as it needs a compatible input method to enable PWMSync. Compatible input methods are PPM, S.Bus, DSM and OPLink. This release also introduces support for OneShot125 capable ESCs, such as the KISS ESCs and all ESCs supported in BLHeli V13 and above. Note that OneShot125 support has the same restrictions as PWMSync for CC and CC3D.
|
||||
@ -10,12 +10,12 @@ Other enhancements include key parts of the GCS translated to Chinese and furthe
|
||||
The full list of features, improvements and bugfixes in this release is accessible here:
|
||||
https://progress.openpilot.org/issues/?filter=12161
|
||||
|
||||
|
||||
Release Notes - OpenPilot - Version RELEASE-15.02
|
||||
|
||||
** Bug
|
||||
* [OP-969] - Input Configuration Wizard has scrollbars showing up and next/previous buttons are pushed down out of sight
|
||||
* [OP-1034] - CCPM Config Widget crashes GCS if required boxes aren't set i.e. Channel set to None
|
||||
* [OP-1236] - Icons on Welcome tab - moves to the left
|
||||
* [OP-1466] - Gcs crashes on Helicopter config tab
|
||||
* [OP-1522] - Improve Robustness of OPLink radio
|
||||
* [OP-1601] - Still not enough ram on CC for gps to be usable
|
||||
@ -38,6 +38,8 @@ Release Notes - OpenPilot - Version RELEASE-15.02
|
||||
* [OP-1755] - Add additional path for cloudconfigs
|
||||
* [OP-1758] - Upgrade hidapi for all OSs (except windows) to solve mac issue:Fix incorrect device list after device removal
|
||||
* [OP-1761] - Wizard bad config when PPM in, RapidESC out and hexa frame with CC/CC3D/Atom
|
||||
* [OP-1764] - System should sanity check RC Input Channel value ranges and raise alarm accordingly
|
||||
* [OP-1768] - PWM Sync and OneShot125 wizard output level and warning are incorrect
|
||||
|
||||
|
||||
** Improvement
|
||||
@ -60,13 +62,13 @@ Release Notes - OpenPilot - Version RELEASE-15.02
|
||||
** Task
|
||||
* [OP-1721] - C++ enable flight controller and upgrade ARM tools
|
||||
* [OP-1738] - change default flight modes and thrust settings
|
||||
* [OP-1747] - 15.02 rc1 motor end points do not reflect oneshot125 / pwmsync
|
||||
|
||||
** Sub task
|
||||
* [OP-1748] - Chinese translation for 15.02
|
||||
* [OP-1752] - Add Alarm sub status to SystemHealth
|
||||
|
||||
|
||||
|
||||
--- RELEASE-15.01 --- Look Ma, No hands ---
|
||||
This release mainly focuses on a new feature, GPSAssist which is a new form of assisted control for multirotors.
|
||||
Assisted Control provides assistance functions on top of existing flight modes. GPSAssist is the
|
||||
|
@ -44,6 +44,7 @@
|
||||
|
||||
// a number of useful macros
|
||||
#define ADDSEVERITY(check) severity = (severity != SYSTEMALARMS_ALARM_OK ? severity : ((check) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_CRITICAL))
|
||||
#define ADDEXTENDEDALARMSTATUS(error_code, error_substatus) if ((severity != SYSTEMALARMS_ALARM_OK) && (alarmstatus == SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE)) { alarmstatus = (error_code); alarmsubstatus = (error_substatus); }
|
||||
|
||||
// private types
|
||||
typedef struct SANITYCHECK_CustomHookInstance {
|
||||
@ -178,6 +179,27 @@ int32_t configuration_check()
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Check throttle/collective channel range for valid configuration of input for critical control
|
||||
SystemSettingsThrustControlOptions thrustType;
|
||||
SystemSettingsThrustControlGet(&thrustType);
|
||||
ManualControlSettingsChannelMinData channelMin;
|
||||
ManualControlSettingsChannelMaxData channelMax;
|
||||
ManualControlSettingsChannelMinGet(&channelMin);
|
||||
ManualControlSettingsChannelMaxGet(&channelMax);
|
||||
switch (thrustType) {
|
||||
case SYSTEMSETTINGS_THRUSTCONTROL_THROTTLE:
|
||||
ADDSEVERITY(fabsf(channelMax.Throttle - channelMin.Throttle) > 300.0f);
|
||||
ADDEXTENDEDALARMSTATUS(SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE, 0);
|
||||
break;
|
||||
case SYSTEMSETTINGS_THRUSTCONTROL_COLLECTIVE:
|
||||
ADDSEVERITY(fabsf(channelMax.Collective - channelMin.Collective) > 300.0f);
|
||||
ADDEXTENDEDALARMSTATUS(SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE, 0);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// query sanity check hooks
|
||||
if (severity < SYSTEMALARMS_ALARM_CRITICAL) {
|
||||
SANITYCHECK_CustomHookInstance *instance = NULL;
|
||||
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@ -0,0 +1,2185 @@
|
||||
{
|
||||
"battery": "2200 4s 60c",
|
||||
"comment": "Bank 1 Acro + \nBank 2 Attitude mode\npids set for Blheli 13.xx and oneshot enabled",
|
||||
"controller": "CC3D",
|
||||
"esc": "Afro 30 Blheli 13.01",
|
||||
"motor": "Blackout 2208 2000kv",
|
||||
"name": "BlackOut B330 ",
|
||||
"nick": "Failsafe",
|
||||
"objects": [
|
||||
{
|
||||
"fields": [
|
||||
{
|
||||
"name": "VbarSensitivity",
|
||||
"type": "float32",
|
||||
"unit": "frac",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0.5
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0.5
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0.5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarRollPI",
|
||||
"type": "float32",
|
||||
"unit": "1/(deg/s)",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.004999999888241291
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0020000000949949026
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarPitchPI",
|
||||
"type": "float32",
|
||||
"unit": "1/(deg/s)",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.004999999888241291
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0020000000949949026
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarYawPI",
|
||||
"type": "float32",
|
||||
"unit": "1/(deg/s)",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.004999999888241291
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0020000000949949026
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarTau",
|
||||
"type": "float32",
|
||||
"unit": "sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "GyroTau",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.004999999888241291
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "DerivativeGamma",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 1
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "AxisLockKp",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 2.5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "WeakLevelingKp",
|
||||
"type": "float32",
|
||||
"unit": "(deg/s)/deg",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.10000000149011612
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlMaxPowerFactor",
|
||||
"type": "float32",
|
||||
"unit": "x",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 3
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlPowerTrim",
|
||||
"type": "float32",
|
||||
"unit": "%",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 100
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlPowerDelayComp",
|
||||
"type": "float32",
|
||||
"unit": "sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.25
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ScaleToAirspeed",
|
||||
"type": "float32",
|
||||
"unit": "m/s",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ScaleToAirspeedLimits",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Min",
|
||||
"value": 0.05000000074505806
|
||||
},
|
||||
{
|
||||
"name": "Max",
|
||||
"value": 3
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "FlightModeMap",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Bank1"
|
||||
},
|
||||
{
|
||||
"name": "1",
|
||||
"value": "Bank2"
|
||||
},
|
||||
{
|
||||
"name": "2",
|
||||
"value": "Bank1"
|
||||
},
|
||||
{
|
||||
"name": "3",
|
||||
"value": "Bank1"
|
||||
},
|
||||
{
|
||||
"name": "4",
|
||||
"value": "Bank1"
|
||||
},
|
||||
{
|
||||
"name": "5",
|
||||
"value": "Bank1"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarGyroSuppress",
|
||||
"type": "int8",
|
||||
"unit": "%",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 30
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarPiroComp",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "FALSE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "VbarMaxAngle",
|
||||
"type": "uint8",
|
||||
"unit": "deg",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 10
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "DerivativeCutoff",
|
||||
"type": "uint8",
|
||||
"unit": "Hz",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 20
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MaxAxisLock",
|
||||
"type": "uint8",
|
||||
"unit": "deg",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 30
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MaxAxisLockRate",
|
||||
"type": "uint8",
|
||||
"unit": "deg/s",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 2
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MaxWeakLevelingRate",
|
||||
"type": "uint8",
|
||||
"unit": "deg/s",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RattitudeModeTransition",
|
||||
"type": "uint8",
|
||||
"unit": "%",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 80
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlMinThrust",
|
||||
"type": "int8",
|
||||
"unit": "%",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlMaxThrust",
|
||||
"type": "uint8",
|
||||
"unit": "%",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 90
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlMaxAngle",
|
||||
"type": "uint8",
|
||||
"unit": "deg",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 105
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlFlightModeSwitchPosEnable",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "FALSE"
|
||||
},
|
||||
{
|
||||
"name": "1",
|
||||
"value": "FALSE"
|
||||
},
|
||||
{
|
||||
"name": "2",
|
||||
"value": "FALSE"
|
||||
},
|
||||
{
|
||||
"name": "3",
|
||||
"value": "FALSE"
|
||||
},
|
||||
{
|
||||
"name": "4",
|
||||
"value": "FALSE"
|
||||
},
|
||||
{
|
||||
"name": "5",
|
||||
"value": "FALSE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlInvertedThrustReversing",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Unreversed"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "CruiseControlInvertedPowerOutput",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Zero"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "LowThrottleZeroIntegral",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "TRUE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "FlightModeAssistMap",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "None"
|
||||
},
|
||||
{
|
||||
"name": "1",
|
||||
"value": "None"
|
||||
},
|
||||
{
|
||||
"name": "2",
|
||||
"value": "None"
|
||||
},
|
||||
{
|
||||
"name": "3",
|
||||
"value": "None"
|
||||
},
|
||||
{
|
||||
"name": "4",
|
||||
"value": "None"
|
||||
},
|
||||
{
|
||||
"name": "5",
|
||||
"value": "None"
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"id": "73603180",
|
||||
"instance": 0,
|
||||
"name": "StabilizationSettings",
|
||||
"setting": true
|
||||
},
|
||||
{
|
||||
"fields": [
|
||||
{
|
||||
"name": "ManualRate",
|
||||
"type": "float32",
|
||||
"unit": "degrees/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 200
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 200
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 220
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MaximumRate",
|
||||
"type": "float32",
|
||||
"unit": "degrees/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 500
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 500
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 300
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.002899999963119626
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0065000001341104507
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 3.4000000596279278e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.004120000172406435
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0082999998703598976
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 4.1999999666586518e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.0086000002920627594
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.014299999922513962
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 4.9999998736893758e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 2.9000000953674316
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 3.2999999523162842
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 2.5
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "AcroInsanityFactor",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.4699999988079071
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleCurve",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.0042716437019407749
|
||||
},
|
||||
{
|
||||
"name": "25",
|
||||
"value": -0.021436728537082672
|
||||
},
|
||||
{
|
||||
"name": "50",
|
||||
"value": -0.051431018859148026
|
||||
},
|
||||
{
|
||||
"name": "75",
|
||||
"value": -0.15000000596046448
|
||||
},
|
||||
{
|
||||
"name": "100",
|
||||
"value": -0.34714511036872864
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 55
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 55
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 35
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "StickExpo",
|
||||
"type": "int8",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 12
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 12
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": -5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "EnablePiroComp",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "FALSE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "EnableThrustPIDScaling",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "TRUE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleSource",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "ActuatorDesiredThrust"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleTarget",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "PD"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleAxes",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Roll Pitch"
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"id": "E8EBBD48",
|
||||
"instance": 0,
|
||||
"name": "StabilizationSettingsBank1",
|
||||
"setting": true
|
||||
},
|
||||
{
|
||||
"fields": [
|
||||
{
|
||||
"name": "ManualRate",
|
||||
"type": "float32",
|
||||
"unit": "degrees/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 200
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 200
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 220
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MaximumRate",
|
||||
"type": "float32",
|
||||
"unit": "degrees/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 500
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 500
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 300
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.00279999990016222
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0054999999701976776
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 2.9000000722589903e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.0036200000904500484
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0086000002920627594
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 3.600000127335079e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.0086000002920627594
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.014299999922513962
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 4.9999998736893758e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 3
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 3.4000000953674316
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 2.5
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "AcroInsanityFactor",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.40000000596046448
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleCurve",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.012843480333685875
|
||||
},
|
||||
{
|
||||
"name": "25",
|
||||
"value": -7.1359904723067302e-06
|
||||
},
|
||||
{
|
||||
"name": "50",
|
||||
"value": -0.12000571191310883
|
||||
},
|
||||
{
|
||||
"name": "75",
|
||||
"value": -0.18857327103614807
|
||||
},
|
||||
{
|
||||
"name": "100",
|
||||
"value": -0.25714081525802612
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 55
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 55
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 35
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "StickExpo",
|
||||
"type": "int8",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 15
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 15
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": -5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "EnablePiroComp",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "FALSE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "EnableThrustPIDScaling",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "TRUE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleSource",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "ActuatorDesiredThrust"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleTarget",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "PD"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleAxes",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Roll Pitch"
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"id": "70E9539A",
|
||||
"instance": 0,
|
||||
"name": "StabilizationSettingsBank2",
|
||||
"setting": true
|
||||
},
|
||||
{
|
||||
"fields": [
|
||||
{
|
||||
"name": "ManualRate",
|
||||
"type": "float32",
|
||||
"unit": "degrees/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 220
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 220
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 220
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MaximumRate",
|
||||
"type": "float32",
|
||||
"unit": "degrees/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 300
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 300
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 300
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.0024999999441206455
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0040000001899898052
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 1.9999999494757503e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.0024999999441206455
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0040000001899898052
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 1.9999999494757503e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawRatePID",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 0.0062000001780688763
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "Kd",
|
||||
"value": 4.9999998736893758e-05
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 2.5
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 2.5
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawPI",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "Kp",
|
||||
"value": 2.5
|
||||
},
|
||||
{
|
||||
"name": "Ki",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ILimit",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "AcroInsanityFactor",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.5
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleCurve",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0.30000001192092896
|
||||
},
|
||||
{
|
||||
"name": "25",
|
||||
"value": 0.15000000596046448
|
||||
},
|
||||
{
|
||||
"name": "50",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "75",
|
||||
"value": -0.15000000596046448
|
||||
},
|
||||
{
|
||||
"name": "100",
|
||||
"value": -0.30000001192092896
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "RollMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 55
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "PitchMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 55
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "YawMax",
|
||||
"type": "uint8",
|
||||
"unit": "degrees",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 35
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "StickExpo",
|
||||
"type": "int8",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "EnablePiroComp",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "TRUE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "EnableThrustPIDScaling",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "FALSE"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleSource",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "ActuatorDesiredThrust"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleTarget",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "PID"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrustPIDScaleAxes",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Roll Pitch"
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"id": "C02DAA6A",
|
||||
"instance": 0,
|
||||
"name": "StabilizationSettingsBank3",
|
||||
"setting": true
|
||||
},
|
||||
{
|
||||
"fields": [
|
||||
{
|
||||
"name": "MaxAccel",
|
||||
"type": "float32",
|
||||
"unit": "units/sec",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 1000
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "FeedForward",
|
||||
"type": "float32",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "AccelTime",
|
||||
"type": "float32",
|
||||
"unit": "ms",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "DecelTime",
|
||||
"type": "float32",
|
||||
"unit": "ms",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "25",
|
||||
"value": 0.22499999403953552
|
||||
},
|
||||
{
|
||||
"name": "50",
|
||||
"value": 0.44999998807907104
|
||||
},
|
||||
{
|
||||
"name": "75",
|
||||
"value": 0.67499995231628418
|
||||
},
|
||||
{
|
||||
"name": "100",
|
||||
"value": 0.89999997615814209
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"type": "float32",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "25",
|
||||
"value": 0.22499999403953552
|
||||
},
|
||||
{
|
||||
"name": "50",
|
||||
"value": 0.44999998807907104
|
||||
},
|
||||
{
|
||||
"name": "75",
|
||||
"value": 0.67499995231628418
|
||||
},
|
||||
{
|
||||
"name": "100",
|
||||
"value": 0.89999997615814209
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MixerValueRoll",
|
||||
"type": "int8",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MixerValuePitch",
|
||||
"type": "int8",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "MixerValueYaw",
|
||||
"type": "int8",
|
||||
"unit": "percent",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": 50
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Curve2Source",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Throttle"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer1Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Motor"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer1Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 127
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 64
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 64
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": -64
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer2Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Motor"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer2Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 127
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": -64
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 64
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 64
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer3Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Motor"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer3Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 127
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": -64
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": -64
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": -64
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer4Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Motor"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer4Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 127
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 64
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": -64
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 64
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer5Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer5Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer6Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer6Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer7Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer7Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer8Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer8Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer9Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer9Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer10Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer10Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer11Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer11Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer12Type",
|
||||
"type": "enum",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "0",
|
||||
"value": "Disabled"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Mixer12Vector",
|
||||
"type": "int8",
|
||||
"unit": "",
|
||||
"values": [
|
||||
{
|
||||
"name": "ThrottleCurve1",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "ThrottleCurve2",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Roll",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Pitch",
|
||||
"value": 0
|
||||
},
|
||||
{
|
||||
"name": "Yaw",
|
||||
"value": 0
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"id": "7BF2CFA8",
|
||||
"instance": 0,
|
||||
"name": "MixerSettings",
|
||||
"setting": true
|
||||
},
|
||||
{
|
||||
"fields": [
|
||||
{
|
||||
"name": "P",
|
||||
"type": "float32",
|
||||
"unit": "1^2",
|
||||
"values": [
|
||||
{
|
||||
"name": "PositionNorth",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "PositionEast",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "PositionDown",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "VelocityNorth",
|
||||
"value": 1
|
||||
},
|
||||
{
|
||||
"name": "VelocityEast",
|
||||
"value": 1
|
||||
},
|
||||
{
|
||||
"name": "VelocityDown",
|
||||
"value": 1
|
||||
},
|
||||
{
|
||||
"name": "AttitudeQ1",
|
||||
"value": 0.0070000002160668373
|
||||
},
|
||||
{
|
||||
"name": "AttitudeQ2",
|
||||
"value": 0.0070000002160668373
|
||||
},
|
||||
{
|
||||
"name": "AttitudeQ3",
|
||||
"value": 0.0070000002160668373
|
||||
},
|
||||
{
|
||||
"name": "AttitudeQ4",
|
||||
"value": 0.0070000002160668373
|
||||
},
|
||||
{
|
||||
"name": "GyroDriftX",
|
||||
"value": 9.9999999747524271e-07
|
||||
},
|
||||
{
|
||||
"name": "GyroDriftY",
|
||||
"value": 9.9999999747524271e-07
|
||||
},
|
||||
{
|
||||
"name": "GyroDriftZ",
|
||||
"value": 9.9999999747524271e-07
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "Q",
|
||||
"type": "float32",
|
||||
"unit": "1^2",
|
||||
"values": [
|
||||
{
|
||||
"name": "GyroX",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "GyroY",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "GyroZ",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "AccelX",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "AccelY",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "AccelZ",
|
||||
"value": 0.0099999997764825821
|
||||
},
|
||||
{
|
||||
"name": "GyroDriftX",
|
||||
"value": 9.9999999747524271e-07
|
||||
},
|
||||
{
|
||||
"name": "GyroDriftY",
|
||||
"value": 9.9999999747524271e-07
|
||||
},
|
||||
{
|
||||
"name": "GyroDriftZ",
|
||||
"value": 9.9999999747524271e-07
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "R",
|
||||
"type": "float32",
|
||||
"unit": "1^2",
|
||||
"values": [
|
||||
{
|
||||
"name": "GPSPosNorth",
|
||||
"value": 1
|
||||
},
|
||||
{
|
||||
"name": "GPSPosEast",
|
||||
"value": 1
|
||||
},
|
||||
{
|
||||
"name": "GPSPosDown",
|
||||
"value": 1000000
|
||||
},
|
||||
{
|
||||
"name": "GPSVelNorth",
|
||||
"value": 0.0010000000474974513
|
||||
},
|
||||
{
|
||||
"name": "GPSVelEast",
|
||||
"value": 0.0010000000474974513
|
||||
},
|
||||
{
|
||||
"name": "GPSVelDown",
|
||||
"value": 0.0010000000474974513
|
||||
},
|
||||
{
|
||||
"name": "MagX",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "MagY",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "MagZ",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "BaroZ",
|
||||
"value": 0.0099999997764825821
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"name": "FakeR",
|
||||
"type": "float32",
|
||||
"unit": "1^2",
|
||||
"values": [
|
||||
{
|
||||
"name": "FakeGPSPosIndoor",
|
||||
"value": 10
|
||||
},
|
||||
{
|
||||
"name": "FakeGPSVelIndoor",
|
||||
"value": 1
|
||||
},
|
||||
{
|
||||
"name": "FakeGPSVelAirspeed",
|
||||
"value": 1000
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"id": "5E91213C",
|
||||
"instance": 0,
|
||||
"name": "EKFConfiguration",
|
||||
"setting": true
|
||||
}
|
||||
],
|
||||
"owner": "Jim ",
|
||||
"propeller": "HQ DD 6 X4.5",
|
||||
"servo": "",
|
||||
"size": "330",
|
||||
"subtype": 2,
|
||||
"type": 1,
|
||||
"uuid": "{5bf30e57-f44b-427d-bfd6-9e9980c55302}",
|
||||
"weight": "1003"
|
||||
}
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@ -30,7 +30,7 @@
|
||||
inkscape:zoom="6.5977991"
|
||||
inkscape:cx="55.083588"
|
||||
inkscape:cy="24.071773"
|
||||
inkscape:current-layer="layer45"
|
||||
inkscape:current-layer="layer46"
|
||||
id="namedview3608"
|
||||
showgrid="true"
|
||||
inkscape:window-width="1280"
|
||||
@ -1685,6 +1685,20 @@
|
||||
ry="0.98050147"
|
||||
inkscape:label="#rect4550-8-1-4-21-1" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer46"
|
||||
inkscape:label="SystemConfiguration-BadThrottleOrCollectiveInputRange">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="SystemConfiguration-BadThrottleOrCollectiveInputRange"
|
||||
width="13.110236"
|
||||
height="10.107105"
|
||||
x="80.806435"
|
||||
y="51.972187"
|
||||
ry="0.98050147"
|
||||
inkscape:label="#rect4550-8-1-4-21-1" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer43"
|
||||
@ -3024,7 +3038,7 @@
|
||||
sodipodi:cy="35.07505"
|
||||
sodipodi:rx="0.5"
|
||||
sodipodi:ry="0.5"
|
||||
d="M 14,35.07505 A 0.5,0.5 0 1 1 13.999725,35.058469"
|
||||
d="M 14,35.07505 C 14,35.351193 13.776142,35.57505 13.5,35.57505 C 13.223858,35.57505 13,35.351193 13,35.07505 C 13,34.798908 13.223858,34.57505 13.5,34.57505 C 13.769688,34.57505 13.990781,34.78893 13.999725,35.058469"
|
||||
sodipodi:start="0"
|
||||
sodipodi:end="6.2500167"
|
||||
sodipodi:open="true"
|
||||
@ -3057,7 +3071,7 @@
|
||||
sodipodi:cy="35.07505"
|
||||
sodipodi:rx="0.5"
|
||||
sodipodi:ry="0.5"
|
||||
d="M 14,35.07505 A 0.5,0.5 0 1 1 13.999725,35.058469"
|
||||
d="M 14,35.07505 C 14,35.351193 13.776142,35.57505 13.5,35.57505 C 13.223858,35.57505 13,35.351193 13,35.07505 C 13,34.798908 13.223858,34.57505 13.5,34.57505 C 13.769688,34.57505 13.990781,34.78893 13.999725,35.058469"
|
||||
sodipodi:start="0"
|
||||
sodipodi:end="6.2500167"
|
||||
sodipodi:open="true"
|
||||
|
Before Width: | Height: | Size: 109 KiB After Width: | Height: | Size: 109 KiB |
@ -549,6 +549,8 @@ void ConfigInputWidget::wzNext()
|
||||
|
||||
// Force flight mode neutral to middle and Throttle neutral at 4%
|
||||
adjustSpecialNeutrals();
|
||||
throttleError = false;
|
||||
checkThrottleRange();
|
||||
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
// move to Arming Settings tab
|
||||
@ -1593,6 +1595,7 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
ui->saveRCInputToRAM->setEnabled(false);
|
||||
ui->saveRCInputToSD->setEnabled(false);
|
||||
ui->runCalibration->setText(tr("Stop Manual Calibration"));
|
||||
throttleError = false;
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("<p>Arming Settings are now set to 'Always Disarmed' for your safety.</p>"
|
||||
@ -1628,11 +1631,6 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
|
||||
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject *)), this, SLOT(updateCalibration()));
|
||||
} else {
|
||||
ui->configurationWizard->setEnabled(true);
|
||||
ui->saveRCInputToRAM->setEnabled(true);
|
||||
ui->saveRCInputToSD->setEnabled(true);
|
||||
ui->runCalibration->setText(tr("Start Manual Calibration"));
|
||||
|
||||
manualCommandData = manualCommandObj->getData();
|
||||
manualSettingsData = manualSettingsObj->getData();
|
||||
|
||||
@ -1641,16 +1639,21 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
for (unsigned int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++) {
|
||||
if ((i == ManualControlSettings::CHANNELNUMBER_FLIGHTMODE) || (i == ManualControlSettings::CHANNELNUMBER_THROTTLE)) {
|
||||
adjustSpecialNeutrals();
|
||||
checkThrottleRange();
|
||||
} else {
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
}
|
||||
}
|
||||
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
|
||||
// Load actuator settings back from beginning of manual calibration
|
||||
actuatorSettingsObj->setData(previousActuatorSettingsData);
|
||||
|
||||
ui->configurationWizard->setEnabled(true);
|
||||
ui->saveRCInputToRAM->setEnabled(true);
|
||||
ui->saveRCInputToSD->setEnabled(true);
|
||||
ui->runCalibration->setText(tr("Start Manual Calibration"));
|
||||
|
||||
disconnect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject *)), this, SLOT(updateCalibration()));
|
||||
}
|
||||
}
|
||||
@ -1671,6 +1674,20 @@ void ConfigInputWidget::adjustSpecialNeutrals()
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]) * 0.04);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::checkThrottleRange()
|
||||
{
|
||||
int throttleRange = abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE] -
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]);
|
||||
if (!throttleError && (throttleRange < 300)) {
|
||||
throttleError = true;
|
||||
QMessageBox::warning(this, tr("Warning"), tr("<p>There is something wrong with Throttle range. Please redo calibration and move <b>ALL sticks</b>, Throttle stick included.</p>"), QMessageBox::Ok);
|
||||
|
||||
// Set Throttle neutral to max value so Throttle can't be positive
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE] =
|
||||
manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE];
|
||||
}
|
||||
}
|
||||
|
||||
bool ConfigInputWidget::shouldObjectBeSaved(UAVObject *object)
|
||||
{
|
||||
// ManualControlCommand no need to be saved
|
||||
|
@ -71,6 +71,7 @@ public:
|
||||
bool shouldObjectBeSaved(UAVObject *object);
|
||||
|
||||
private:
|
||||
bool throttleError;
|
||||
bool growing;
|
||||
bool reverse[ManualControlSettings::CHANNELNEUTRAL_NUMELEM];
|
||||
txMovements currentMovement;
|
||||
@ -199,6 +200,7 @@ private slots:
|
||||
void invertControls();
|
||||
void simpleCalibration(bool state);
|
||||
void adjustSpecialNeutrals();
|
||||
void checkThrottleRange();
|
||||
void updateCalibration();
|
||||
void resetChannelSettings();
|
||||
void resetActuatorSettings();
|
||||
|
@ -472,7 +472,7 @@ void ConfigOutputWidget::updateWarnings(UAVObject *)
|
||||
if (systemAlarms.Alarm[SystemAlarms::ALARM_SYSTEMCONFIGURATION] > SystemAlarms::ALARM_WARNING) {
|
||||
switch (systemAlarms.ExtendedAlarmStatus[SystemAlarms::EXTENDEDALARMSTATUS_SYSTEMCONFIGURATION]) {
|
||||
case SystemAlarms::EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT:
|
||||
setWarning(tr("OneShot only works with Receiver Port settings marked with '+OneShot'<br>"
|
||||
setWarning(tr("OneShot and PWMSync output only works with Receiver Port settings marked with '+OneShot'<br>"
|
||||
"When using Receiver Port setting 'PPM_PIN8+OneShot' "
|
||||
"<b><font color='%1'>Bank %2</font></b> must be set to PWM")
|
||||
.arg(m_banks.at(3).color().name()).arg(m_banks.at(3).label()->text()));
|
||||
|
@ -85,6 +85,15 @@ void EscCalibrationPage::resetAllSecurityCheckboxes()
|
||||
ui->securityCheckBox3->setChecked(false);
|
||||
}
|
||||
|
||||
int EscCalibrationPage::getHighOutputRate()
|
||||
{
|
||||
if (getWizard()->getEscType() == SetupWizard::ESC_ONESHOT) {
|
||||
return HIGH_ONESHOT125_OUTPUT_PULSE_LENGTH_MICROSECONDS;
|
||||
} else {
|
||||
return HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS;
|
||||
}
|
||||
}
|
||||
|
||||
void EscCalibrationPage::startButtonClicked()
|
||||
{
|
||||
if (!m_isCalibrating) {
|
||||
@ -95,7 +104,7 @@ void EscCalibrationPage::startButtonClicked()
|
||||
ui->outputLow->setEnabled(false);
|
||||
ui->nonconnectedLabel->setEnabled(false);
|
||||
ui->connectedLabel->setEnabled(true);
|
||||
ui->outputLevel->setText(QString(tr("%1 µs")).arg(HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS));
|
||||
ui->outputLevel->setText(QString(tr("%1 µs")).arg(getHighOutputRate()));
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *uavoManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavoManager);
|
||||
@ -123,7 +132,7 @@ void EscCalibrationPage::startButtonClicked()
|
||||
}
|
||||
m_outputUtil.startChannelOutput(m_outputChannels, OFF_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS);
|
||||
QThread::msleep(100);
|
||||
m_outputUtil.setChannelOutputValue(HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS);
|
||||
m_outputUtil.setChannelOutputValue(getHighOutputRate());
|
||||
|
||||
ui->stopButton->setEnabled(true);
|
||||
}
|
||||
|
@ -56,10 +56,12 @@ private:
|
||||
static const int LOW_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS = 1050;
|
||||
static const int OFF_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS = 900;
|
||||
static const int HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS = 1900;
|
||||
static const int HIGH_ONESHOT125_OUTPUT_PULSE_LENGTH_MICROSECONDS = 2000;
|
||||
Ui::EscCalibrationPage *ui;
|
||||
bool m_isCalibrating;
|
||||
OutputCalibrationUtil m_outputUtil;
|
||||
QList<quint16> m_outputChannels;
|
||||
int getHighOutputRate();
|
||||
};
|
||||
|
||||
#endif // ESCCALIBRATIONPAGE_H
|
||||
|
@ -77,32 +77,32 @@ void OutputCalibrationPage::setupActuatorMinMaxAndNeutral(int motorChannelStart,
|
||||
for (int servoid = 0; servoid < 12; servoid++) {
|
||||
if (servoid >= motorChannelStart && servoid <= motorChannelEnd) {
|
||||
// Set to motor safe values
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1000;
|
||||
m_actuatorSettings[servoid].channelMax = 1900;
|
||||
m_actuatorSettings[servoid].channelMin = LOW_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].channelNeutral = LOW_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].channelMax = getHighOutputRate();
|
||||
m_actuatorSettings[servoid].isReversableMotor = false;
|
||||
// Car and Tank should use reversable Esc/motors
|
||||
if ((getWizard()->getVehicleSubType() == SetupWizard::GROUNDVEHICLE_CAR)
|
||||
|| (getWizard()->getVehicleSubType() == SetupWizard::GROUNDVEHICLE_DIFFERENTIAL)) {
|
||||
m_actuatorSettings[servoid].channelNeutral = 1500;
|
||||
m_actuatorSettings[servoid].channelNeutral = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].isReversableMotor = true;
|
||||
// Set initial output value
|
||||
m_calibrationUtil->startChannelOutput(servoid, 1500);
|
||||
m_calibrationUtil->startChannelOutput(servoid, NEUTRAL_OUTPUT_RATE_MILLISECONDS);
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
}
|
||||
} else if (servoid < totalUsedChannels) {
|
||||
// Set to servo safe values
|
||||
m_actuatorSettings[servoid].channelMin = 1500;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1500;
|
||||
m_actuatorSettings[servoid].channelMax = 1500;
|
||||
m_actuatorSettings[servoid].channelMin = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].channelNeutral = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].channelMax = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
|
||||
// Set initial servo output value
|
||||
m_calibrationUtil->startChannelOutput(servoid, 1500);
|
||||
m_calibrationUtil->startChannelOutput(servoid, NEUTRAL_OUTPUT_RATE_MILLISECONDS);
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
} else {
|
||||
// "Disable" these channels
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1000;
|
||||
m_actuatorSettings[servoid].channelMax = 1000;
|
||||
m_actuatorSettings[servoid].channelMin = LOW_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].channelNeutral = LOW_OUTPUT_RATE_MILLISECONDS;
|
||||
m_actuatorSettings[servoid].channelMax = LOW_OUTPUT_RATE_MILLISECONDS;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -660,6 +660,15 @@ void OutputCalibrationPage::debugLogChannelValues()
|
||||
qDebug() << "ChannelMax : " << m_actuatorSettings[currentChannel].channelMax;
|
||||
}
|
||||
|
||||
int OutputCalibrationPage::getHighOutputRate()
|
||||
{
|
||||
if (getWizard()->getEscType() == SetupWizard::ESC_ONESHOT) {
|
||||
return HIGH_OUTPUT_RATE_MILLISECONDS_ONESHOT125;
|
||||
} else {
|
||||
return HIGH_OUTPUT_RATE_MILLISECONDS_PWM;
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value)
|
||||
{
|
||||
Q_UNUSED(value);
|
||||
|
@ -74,6 +74,11 @@ private slots:
|
||||
|
||||
private:
|
||||
enum ElementType { FULL, FRAME, MOTOR, SERVO };
|
||||
static const int LOW_OUTPUT_RATE_MILLISECONDS = 1000;
|
||||
static const int NEUTRAL_OUTPUT_RATE_MILLISECONDS = 1500;
|
||||
static const int HIGH_OUTPUT_RATE_MILLISECONDS_PWM = 1900;
|
||||
static const int HIGH_OUTPUT_RATE_MILLISECONDS_ONESHOT125 = 2000;
|
||||
|
||||
void setupVehicle();
|
||||
void startWizard();
|
||||
void setupVehicleItems();
|
||||
@ -86,8 +91,11 @@ private:
|
||||
quint16 value, quint16 safeValue, QSlider *slider);
|
||||
bool checkAlarms();
|
||||
void debugLogChannelValues();
|
||||
|
||||
void getCurrentChannels(QList<quint16> &channels);
|
||||
void enableAllMotorsCheckBox(bool enable);
|
||||
int getHighOutputRate();
|
||||
quint16 getCurrentChannel();
|
||||
|
||||
Ui::OutputCalibrationPage *ui;
|
||||
QSvgRenderer *m_vehicleRenderer;
|
||||
|
@ -0,0 +1,17 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>System Configuration : BadThrottleOrCollectiveInputRange</h1>
|
||||
<p>
|
||||
There is a problem with throttle/collective channel configuration :
|
||||
<ul>
|
||||
<li>Redo your input calibration.</li>
|
||||
<li>The range for the channel between min and max must be more than 300us.</li>
|
||||
</ul>
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -0,0 +1,17 @@
|
||||
<html>
|
||||
<head>
|
||||
<title></title>
|
||||
<meta content="">
|
||||
<style></style>
|
||||
</head>
|
||||
<body>
|
||||
<h1>Configuration Système : BadThrottleOrCollectiveInputRange</h1>
|
||||
<p>
|
||||
Il y a un problème avec la configuration du canal throttle/collective :
|
||||
<ul>
|
||||
<li>Relancez la calibration des entrées.</li>
|
||||
<li>La différence entre la valeur mini et maxi doit faire au moins 300µs.</li>
|
||||
</ul>
|
||||
</p>
|
||||
</body>
|
||||
</html>
|
@ -33,6 +33,7 @@
|
||||
<file>html/Stabilization-Critical.html</file>
|
||||
<file>html/SystemConfiguration-UnsupportedConfig_OneShot.html</file>
|
||||
<file>html/SystemConfiguration-FlightMode.html</file>
|
||||
<file>html/SystemConfiguration-BadThrottleOrCollectiveInputRange.html</file>
|
||||
<file>html/BootFault-RebootRequired.html</file>
|
||||
</qresource>
|
||||
<qresource prefix="/systemhealth" lang="fr">
|
||||
@ -69,6 +70,7 @@
|
||||
<file alias="html/Stabilization-Critical.html">html/fr/Stabilization-Critical.html</file>
|
||||
<file alias="html/SystemConfiguration-UnsupportedConfig_OneShot.html">html/fr/SystemConfiguration-UnsupportedConfig_OneShot.html</file>
|
||||
<file alias="html/SystemConfiguration-FlightMode.html">html/fr/SystemConfiguration-FlightMode.html</file>
|
||||
<file alias="html/SystemConfiguration-BadThrottleOrCollectiveInputRange.html">html/fr/SystemConfiguration-BadThrottleOrCollectiveInputRange.html</file>
|
||||
<file alias="html/BootFault-RebootRequired.html">html/fr/BootFault-RebootRequired.html</file>
|
||||
</qresource>
|
||||
|
||||
|
@ -36,6 +36,7 @@
|
||||
<option>RebootRequired</option>
|
||||
<option>FlightMode</option>
|
||||
<option>UnsupportedConfig_OneShot</option>
|
||||
<option>BadThrottleOrCollectiveInputRange</option>
|
||||
</options>
|
||||
</field>
|
||||
<field name="ExtendedAlarmSubStatus" units="" type="uint8" defaultvalue="0">
|
||||
|
Loading…
Reference in New Issue
Block a user