Unverified Commit d3ef1500 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge branch 'master' into SimpleFlightModes

parents 6bed47a9 d6ad774b
......@@ -8,6 +8,7 @@ Note: This file only contains high level features or important fixes.
* ArduPilot: Copter - Add suppor for Simple and Super Simple flight modes
* ArduPilot: Flight Mode setup - Switch Options were not showing up for all firmware revs
* ArduCopter: Add PID Tuning page to Tuning Setup
* ArduPilot: Copter - Advanced Tuning support
* ArduPilot: Rover - Frame setup support
* ArduPilot: Copter - Update support to 3.5+
......@@ -21,12 +22,21 @@ Note: This file only contains high level features or important fixes.
* ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page.
* Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans.
### 3.5.1 - Not yet released
### 3.5.3 - Not yet released
* Fix crash when clicking on GeoFence polygon vertex
* PX4: Fix missing ```MC_YAW_FF``` parameter in PID Tuning
* ArduPilot: Fix parameter file save generating bad characters from git hash
### 3.5.2 - Stable
* Fix Ubuntu AppImage startup failure
### 3.5.1
* Update Windows usb drivers
* Add ArduPilot CubeBlack Service Bulletin check
* Fix visibility of PX4/ArduPilot logo in toolbar
* Fix tile set count but in OfflineMaps which would cause image and elevation tile set to have incorrect counts and be incorrectly marked as download incomplete.
### 3.5.0 - Stable
### 3.5.0
* Plan GeoFence: Fix loading of fence from intermediate 3.4 code
* Structure Scan: Fix loading of structure scan height
* ArduPilot: Fix location of planned home position when not connected to vehicle. Issue #6840.
......
......@@ -138,8 +138,9 @@ LinuxBuild {
!contains(DEFINES, __rasp_pi2__) {
# Some Qt distributions link with *.so.56
QT_LIB_LIST += \
libicudata.so* \
libicuuc.so*
libicudata.so.56 \
libicui18n.so.56 \
libicuuc.so.56
}
for(QT_LIB, QT_LIB_LIST) {
......
No preview for this file type
......@@ -201,7 +201,7 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(void)
if (paramMgr->parameterExists(-1, paramAcc3) && paramMgr->getParameter(-1, paramAcc3)->rawValue().toInt() == 0 &&
paramMgr->parameterExists(-1, paramGyr3) && paramMgr->getParameter(-1, paramGyr3)->rawValue().toInt() == 0 &&
paramMgr->parameterExists(-1, paramEnableMask) && paramMgr->getParameter(-1, paramEnableMask)->rawValue().toInt() >= 7) {
qgcApp()->showMessage(tr("WARNING: The flight board you are using has a critical service bulletin against ti which advise against flying. https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406"));
qgcApp()->showMessage(tr("WARNING: The flight board you are using has a critical service bulletin against it which advises against flying. For details see: https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406"));
}
}
......
......@@ -61,26 +61,6 @@ SetupPage {
max: 15
step: 1
}
/*
These seem to have disappeared from PX4 firmware!
ListElement {
title: qsTr("Roll sensitivity")
description: qsTr("Slide to the left to make roll control faster and more accurate. Slide to the right if roll oscillates or is too twitchy.")
param: "MC_ROLL_TC"
min: 0.15
max: 0.25
step: 0.01
}
ListElement {
title: qsTr("Pitch sensitivity")
description: qsTr("Slide to the left to make pitch control faster and more accurate. Slide to the right if pitch oscillates or is too twitchy.")
param: "MC_PITCH_TC"
min: 0.15
max: 0.25
step: 0.01
}
*/
}
}
......@@ -112,7 +92,6 @@ SetupPage {
controller.getParameterFact(-1, "MC_YAWRATE_P"),
controller.getParameterFact(-1, "MC_YAWRATE_I"),
controller.getParameterFact(-1, "MC_YAWRATE_D"),
controller.getParameterFact(-1, "MC_YAW_FF"),
controller.getParameterFact(-1, "MC_YAWRATE_FF") ] ]
}
} // Component - Advanced Page
......
......@@ -46,7 +46,8 @@ void FactGroup::_setupTimer()
if (_updateRateMSecs > 0) {
connect(&_updateTimer, &QTimer::timeout, this, &FactGroup::_updateAllValues);
_updateTimer.setSingleShot(false);
_updateTimer.start(_updateRateMSecs);
_updateTimer.setInterval(_updateRateMSecs);
_updateTimer.start();
}
}
......@@ -125,3 +126,19 @@ void FactGroup::_updateAllValues(void)
fact->sendDeferredValueChangedSignal();
}
}
void FactGroup::setLiveUpdates(bool liveUpdates)
{
if (_updateTimer.interval() == 0) {
return;
}
if (liveUpdates) {
_updateTimer.stop();
} else {
_updateTimer.start();
}
for(Fact* fact: _nameToFactMap) {
fact->setSendValueChangedSignals(liveUpdates);
}
}
......@@ -38,6 +38,9 @@ public:
/// @return FactGroup for specified name, NULL if not found
Q_INVOKABLE FactGroup* getFactGroup(const QString& name);
/// Turning on live updates will allow value changes to flow through as they are received.
Q_INVOKABLE void setLiveUpdates(bool liveUpdates);
QStringList factNames(void) const { return _factNames; }
QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); }
......
......@@ -644,6 +644,29 @@ Note: ekf2 will limit the delta velocity bias estimate magnitude to be less than
<long_desc>The default allows to arm the vehicle without GPS signal.</long_desc>
<boolean />
</parameter>
<parameter category="Developer" default="0" name="COM_ASPD_FS_ACT" type="INT32">
<short_desc>Airspeed fault detection (Experimental)</short_desc>
<long_desc>Failsafe action when bad airspeed measurements are detected. Ensure the COM_ASPD_STALL parameter is set correctly before use.</long_desc>
<values>
<value code="0">disabled</value>
<value code="1">log a message</value>
<value code="2">log a message, warn the user</value>
<value code="3">log a message, warn the user, switch to non-airspeed TECS mode</value>
<value code="4">log a message, warn the user, switch to non-airspeed TECS mode, switch to Return mode after COM_ASPD_FS_DLY seconds</value>
</values>
</parameter>
<parameter category="Developer" default="0" name="COM_ASPD_FS_DLY" type="INT32">
<short_desc>Airspeed fault detection delay before RTL (Experimental)</short_desc>
<long_desc>RTL delay after bad airspeed measurements are detected if COM_ASPD_FS_ACT is set to 4. Ensure the COM_ASPD_STALL parameter is set correctly before use. The failsafe start and stop delays are controlled by the COM_TAS_FS_T1 and COM_TAS_FS_T2 parameters. Additional protection against persistent airspeed sensor errors can be enabled using the COM_TAS_FS_INNOV parameter, but these addtional checks are more prone to false positives in windy conditions.</long_desc>
<min>0</min>
<max>300</max>
<unit>s</unit>
</parameter>
<parameter category="Developer" default="10.0" name="COM_ASPD_STALL" type="FLOAT">
<short_desc>Airspeed fault detection stall airspeed. (Experimental)</short_desc>
<long_desc>This is the minimum indicated airspeed at which the wing can produce 1g of lift. It is used by the airspeed sensor fault detection and failsafe calculation to detect a significant airspeed low measurement error condition and should be set based on flight test for reliable operation. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter.</long_desc>
<unit>m/s</unit>
</parameter>
<parameter default="-1.0" name="COM_DISARM_LAND" type="FLOAT">
<short_desc>Time-out for auto disarm after landing</short_desc>
<long_desc>A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. The vehicle will also auto-disarm right after arming if it has not even flown, however the time will always be 10 seconds such that the pilot has enough time to take off. A negative value means that automatic disarming triggered by landing detection is disabled.</long_desc>
......@@ -872,6 +895,14 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action</short_desc>
<unit>s</unit>
<increment>1</increment>
</parameter>
<parameter default="0" name="COM_POSCTL_NAVL" type="INT32">
<short_desc>Position control navigation loss response</short_desc>
<long_desc>This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes.</long_desc>
<values>
<value code="0">Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL.</value>
<value code="1">Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION.</value>
</values>
</parameter>
<parameter default="1" name="COM_POS_FS_DELAY" type="INT32">
<short_desc>Loss of position failsafe activation delay</short_desc>
<long_desc>This sets number of seconds that the position checks need to be failed before the failsafe will activate. The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used.</long_desc>
......@@ -942,6 +973,32 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action</short_desc>
<decimal>0</decimal>
<increment>0.05</increment>
</parameter>
<parameter category="Developer" default="1.0" name="COM_TAS_FS_INNOV" type="FLOAT">
<short_desc>Airspeed failsafe consistency threshold (Experimental)</short_desc>
<long_desc>This specifies the minimum airspeed test ratio as logged in estimator_status.tas_test_ratio required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Start with a value of 1.0 when tuning. When estimator_status.tas_test_ratio is &gt; 1.0 it indicates the inconsistency between predicted and measured airspeed is large enough to cause the navigation EKF to reject airspeed measurements. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the COM_TAS_FS_INTEG parameter. The subsequent failsafe response is controlled by the COM_ASPD_FS_ACT parameter.</long_desc>
<min>0.5</min>
<max>3.0</max>
</parameter>
<parameter category="Developer" default="-1.0" name="COM_TAS_FS_INTEG" type="FLOAT">
<short_desc>Airspeed failsafe consistency delay (Experimental)</short_desc>
<long_desc>This sets the time integral of airspeed test ratio exceedance above COM_TAS_FS_INNOV required to trigger a failsafe. For example if COM_TAS_FS_INNOV is 100 and estimator_status.tas_test_ratio is 2.0, then the exceedance is 1.0 and the integral will rise at a rate of 1.0/second. A negative value disables the check. Larger positive values make the check less sensitive, smaller positive values make it more sensitive. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter.</long_desc>
<max>30.0</max>
<unit>s</unit>
</parameter>
<parameter category="Developer" default="3" name="COM_TAS_FS_T1" type="INT32">
<short_desc>Airspeed failsafe stop delay (Experimental)</short_desc>
<long_desc>Delay before stopping use of airspeed sensor if checks indicate sensor is bad. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter.</long_desc>
<min>1</min>
<max>10</max>
<unit>s</unit>
</parameter>
<parameter category="Developer" default="100" name="COM_TAS_FS_T2" type="INT32">
<short_desc>Airspeed failsafe start delay (Experimental)</short_desc>
<long_desc>Delay before switching back to using airspeed sensor if checks indicate sensor is good. The failsafe response is controlled by the COM_ASPD_FS_ACT parameter.</long_desc>
<min>10</min>
<max>1000</max>
<unit>s</unit>
</parameter>
<parameter default="1" name="COM_VEL_FS_EVH" type="FLOAT">
<short_desc>Horizontal velocity error threshold</short_desc>
<long_desc>This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.</long_desc>
......@@ -3862,14 +3919,6 @@ Used to calculate increased terrain random walk nosie due to movement</short_des
<short_desc>Flag to enable obstacle avoidance</short_desc>
<boolean />
</parameter>
<parameter default="0" name="COM_POSCTL_NAVL" type="INT32">
<short_desc>Position control navigation loss response</short_desc>
<long_desc>This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes.</long_desc>
<values>
<value code="0">Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL.</value>
<value code="1">Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION.</value>
</values>
</parameter>
<parameter default="0" name="COM_TAKEOFF_ACT" type="INT32">
<short_desc>Action after TAKEOFF has been accepted</short_desc>
<long_desc>The mode transition after TAKEOFF has completed successfully.</long_desc>
......
......@@ -106,14 +106,6 @@ void MissionCommandTree::_collapseHierarchy(Vehicle*
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
for (MAV_CMD command: cmdList->commandIds()) {
// Only add supported command to tree (MAV_CMD_NAV_LAST is used for planned home position)
if (!qgcApp()->runningUnitTests()
&& !vehicle->firmwarePlugin()->supportedMissionCommands().isEmpty()
&& !vehicle->firmwarePlugin()->supportedMissionCommands().contains(command)
&& command != MAV_CMD_NAV_LAST) {
continue;
}
MissionCommandUIInfo* uiInfo = cmdList->getUIInfo(command);
if (uiInfo) {
if (collapsedTree.contains(command)) {
......@@ -125,22 +117,20 @@ void MissionCommandTree::_collapseHierarchy(Vehicle*
}
}
void MissionCommandTree::_buildAvailableCommands(Vehicle* vehicle)
void MissionCommandTree::_buildAllCommands(Vehicle* vehicle)
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
if (_availableCommands.contains(baseFirmwareType) &&
_availableCommands[baseFirmwareType].contains(baseVehicleType)) {
// Available commands list already built
if (_allCommands.contains(baseFirmwareType) &&
_allCommands[baseFirmwareType].contains(baseVehicleType)) {
// Already built
return;
}
// Build new available commands list
QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree = _availableCommands[baseFirmwareType][baseVehicleType];
QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree = _allCommands[baseFirmwareType][baseVehicleType];
// Any Firmware, Any Vehicle
_collapseHierarchy(vehicle, _staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC], collapsedTree);
......@@ -160,16 +150,17 @@ void MissionCommandTree::_buildAvailableCommands(Vehicle* vehicle)
}
}
// Build category list
QMapIterator<MAV_CMD, MissionCommandUIInfo*> iter(collapsedTree);
while (iter.hasNext()) {
iter.next();
QString newCategory = iter.value()->category();
if (!_availableCategories[baseFirmwareType][baseVehicleType].contains(newCategory)) {
_availableCategories[baseFirmwareType][baseVehicleType].append(newCategory);
// Build category list from supported commands
QList<MAV_CMD> supportedCommands = vehicle->firmwarePlugin()->supportedMissionCommands();
for (MAV_CMD cmd: collapsedTree.keys()) {
if (supportedCommands.contains(cmd)) {
QString newCategory = collapsedTree[cmd]->category();
if (!_supportedCategories[baseFirmwareType][baseVehicleType].contains(newCategory)) {
_supportedCategories[baseFirmwareType][baseVehicleType].append(newCategory);
}
}
}
_availableCategories[baseFirmwareType][baseVehicleType].append(_allCommandsCategory);
_supportedCategories[baseFirmwareType][baseVehicleType].append(_allCommandsCategory);
}
QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle)
......@@ -178,9 +169,9 @@ QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle)
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
_buildAvailableCommands(vehicle);
_buildAllCommands(vehicle);
return _availableCategories[baseFirmwareType][baseVehicleType];
return _supportedCategories[baseFirmwareType][baseVehicleType];
}
QString MissionCommandTree::friendlyName(MAV_CMD command)
......@@ -191,7 +182,7 @@ QString MissionCommandTree::friendlyName(MAV_CMD command)
if (uiInfo) {
return uiInfo->friendlyName();
} else {
return QString("MAV_CMD(%1)").arg((int)command);
return QStringLiteral("MAV_CMD(%1)").arg((int)command);
}
}
......@@ -203,7 +194,7 @@ QString MissionCommandTree::rawName(MAV_CMD command)
if (uiInfo) {
return uiInfo->rawName();
} else {
return QString("MAV_CMD(%1)").arg((int)command);
return QStringLiteral("MAV_CMD(%1)").arg((int)command);
}
}
......@@ -218,13 +209,13 @@ const MissionCommandUIInfo* MissionCommandTree::getUIInfo(Vehicle* vehicle, MAV_
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
_buildAvailableCommands(vehicle);
_buildAllCommands(vehicle);
const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _availableCommands[baseFirmwareType][baseVehicleType];
const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _allCommands[baseFirmwareType][baseVehicleType];
if (infoMap.contains(command)) {
return infoMap[command];
} else {
return NULL;
return nullptr;
}
}
......@@ -232,21 +223,19 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
QList<MAV_CMD> supportedCommands = vehicle->firmwarePlugin()->supportedMissionCommands();
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
_buildAvailableCommands(vehicle);
_buildAllCommands(vehicle);
QVariantList list;
QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _availableCommands[baseFirmwareType][baseVehicleType];
QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _allCommands[baseFirmwareType][baseVehicleType];
for (MAV_CMD command: commandMap.keys()) {
if (command == MAV_CMD_NAV_LAST) {
// MAV_CMD_NAV_LAST is used for Mission Settings item. Although we want to be able to get command info for it.
// The user should not be able to use it as a command.
continue;
}
MissionCommandUIInfo* uiInfo = commandMap[command];
if (uiInfo->category() == category || category == _allCommandsCategory) {
list.append(QVariant::fromValue(uiInfo));
if (supportedCommands.contains(command)) {
MissionCommandUIInfo* uiInfo = commandMap[command];
if (uiInfo->category() == category || category == _allCommandsCategory) {
list.append(QVariant::fromValue(uiInfo));
}
}
}
......
......@@ -41,7 +41,7 @@ class MissionCommandTreeTest;
/// For known firmwares, the override files are requested from the FirmwarePlugin.
///
/// When ui info is requested for a specific vehicle the static hierarchy in _staticCommandTree is collapsed into the set of available commands in
/// _availableCommands taking into account the appropriate set of overrides for the MAV_AUTOPILOT/MAV_TYPE combination associated with the vehicle.
/// _allCommands taking into account the appropriate set of overrides for the MAV_AUTOPILOT/MAV_TYPE combination associated with the vehicle.
///
class MissionCommandTree : public QGCTool
{
......@@ -68,12 +68,12 @@ public:
virtual void setToolbox(QGCToolbox* toolbox);
private:
void _collapseHierarchy(Vehicle* vehicle, const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree);
MAV_TYPE _baseVehicleType(MAV_TYPE mavType) const;
MAV_AUTOPILOT _baseFirmwareType(MAV_AUTOPILOT firmwareType) const;
void _buildAvailableCommands(Vehicle* vehicle);
QStringList _availableCategoriesForVehicle(Vehicle* vehicle);
void _baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const;
void _collapseHierarchy(Vehicle* vehicle, const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree);
MAV_TYPE _baseVehicleType(MAV_TYPE mavType) const;
MAV_AUTOPILOT _baseFirmwareType(MAV_AUTOPILOT firmwareType) const;
void _buildAllCommands(Vehicle* vehicle);
QStringList _availableCategoriesForVehicle(Vehicle* vehicle);
void _baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const;
private:
QString _allCommandsCategory; ///< Category which contains all available commands
......@@ -85,10 +85,10 @@ private:
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, MissionCommandList*>> _staticCommandTree;
/// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QMap<MAV_CMD, MissionCommandUIInfo*>>> _availableCommands;
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QMap<MAV_CMD, MissionCommandUIInfo*>>> _allCommands;
/// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList>> _availableCategories;
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList /* category */>> _supportedCategories;
#ifdef UNITTEST_BUILD
......
......@@ -20,6 +20,7 @@ import QGroundControl.FlightMap 1.0
/// GeoFence map visuals
Item {
id: _root
z: QGroundControl.zOrderMapItems
property var map
......@@ -88,10 +89,15 @@ Item {
_paramCircleFenceComponent.destroy()
}
// By default the parent for Instantiator.delegate item is the Instatiator itself. By there is a bug
// in Qt which will cause a crash if this delete item has Menu item within it. Since the Menu item
// doesn't like having a non-visual item as parent. This is likely related to hybrid QQuickWidtget+QML
// Hence Qt folks are going to care. In order to workaround you have to parent the item to _root Item instead.
Instantiator {
model: _polygons
delegate : QGCMapPolygonVisuals {
parent: _root
mapControl: map
mapPolygon: object
borderWidth: object.inclusion ? _borderWidthInclusion : _borderWidthExclusion
......@@ -105,6 +111,7 @@ Item {
model: _circles
delegate : QGCMapCircleVisuals {
parent: _root
mapControl: map
mapCircle: object
borderWidth: object.inclusion ? _borderWidthInclusion : _borderWidthExclusion
......
......@@ -34,6 +34,8 @@ Column {
property real _margins: ScreenTools.defaultFontPixelHeight
property bool _loadComplete: false
Component.onCompleted: _loadComplete = true
FactPanelController {
id: controller
factPanel: qgcViewPanel
......@@ -71,10 +73,22 @@ Column {
font.family: ScreenTools.demiboldFontFamily
}
FactValueSlider {
digitCount: fact.maxString.length
incrementSlots: 3
fact: controller.getParameterFact(-1, param)
Slider {
anchors.left: parent.left
anchors.right: parent.right
minimumValue: min
maximumValue: max
stepSize: step
tickmarksEnabled: true
value: _fact.value
property Fact _fact: controller.getParameterFact(-1, param)
onValueChanged: {
if (_loadComplete) {
_fact.value = value
}
}
}
QGCLabel {
......
......@@ -142,9 +142,12 @@ RowLayout {
}
Component.onCompleted: {
_activeVehicle.setPIDTuningTelemetryMode(true)
saveTuningParamValues()
}
Component.onDestruction: _activeVehicle.setPIDTuningTelemetryMode(false)
on_CurrentTuneTypeChanged: {
saveTuningParamValues()
resetGraphs()
......@@ -159,7 +162,8 @@ RowLayout {
min: 0
max: 0
labelFormat: "%d"
titleText: "sec"
titleText: "msec"
tickCount: 11
}
ValueAxis {
......@@ -167,7 +171,8 @@ RowLayout {
min: 0
max: 0
labelFormat: "%d"
titleText: "sec"
titleText: "msec"
tickCount: 11
}
ValueAxis {
......@@ -193,40 +198,28 @@ RowLayout {
repeat: true
onTriggered: {
var seconds = _msecs / 1000
_valueXAxis.max = seconds
_valueRateXAxis.max = seconds
_valueXAxis.max = _msecs
_valueRateXAxis.max = _msecs
getValues()
valueSeries.append(seconds, _value)
valueSeries.append(_msecs, _value)
adjustYAxisMin(_valueYAxis, _value)
adjustYAxisMax(_valueYAxis, _value)
valueSetpointSeries.append(seconds, _valueSetpoint)
valueSetpointSeries.append(_msecs, _valueSetpoint)
adjustYAxisMin(_valueYAxis, _valueSetpoint)
adjustYAxisMax(_valueYAxis, _valueSetpoint)
valueRateSeries.append(seconds, _valueRate)
valueRateSeries.append(_msecs, _valueRate)
adjustYAxisMin(_valueRateYAxis, _valueRate)
adjustYAxisMax(_valueRateYAxis, _valueRate)
valueRateSetpointSeries.append(seconds, _valueRateSetpoint)
valueRateSetpointSeries.append(_msecs, _valueRateSetpoint)
adjustYAxisMin(_valueRateYAxis, _valueRateSetpoint)
adjustYAxisMax(_valueRateYAxis, _valueRateSetpoint)
_msecs += interval
/*
Testing with just start/stop for now. No time limit.
if (valueSeries.count > _maxPointCount) {
valueSeries.remove(0)
valueSetpointSeries.remove(0)
valueRateSeries.remove(0)
valueRateSetpointSeries.remove(0)
valueXAxis.min = valueSeries.at(0).x
valueRateXAxis.min = valueSeries.at(0).x
}
*/
}
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
......@@ -237,25 +230,25 @@ RowLayout {
spacing: _margins
Layout.alignment: Qt.AlignTop
QGCLabel { text: qsTr("Tuning Axis:") }
Column {
QGCLabel { text: qsTr("Tuning Axis:") }
RowLayout {
spacing: _margins
RowLayout {
spacing: _margins
Repeater {
model: tuneList
QGCRadioButton {
text: modelData
checked: _currentTuneType === modelData
exclusiveGroup: tuneTypeRadios
Repeater {
model: tuneList
QGCRadioButton {
text: modelData
checked: _currentTuneType === modelData
exclusiveGroup: tuneTypeRadios
onClicked: _currentTuneType = modelData
onClicked: _currentTuneType = modelData
}
}
}
}
Item { width: 1; height: 1 }
QGCLabel { text: qsTr("Tuning Values:") }
GridLayout {
......@@ -279,7 +272,10 @@ RowLayout {
text: "-"
onClicked: {
var value = modelData.value
modelData.value -= value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value
var newValue = value - (value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value)
if (newValue >= modelData.min) {
modelData.value = newValue
}
}
}
}
......@@ -301,7 +297,10 @@ RowLayout {
text: "+"
onClicked: {
var value = modelData.value
modelData.value += value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value
var newValue = value + (value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value)
if (newValue <= modelData.max) {
modelData.value = newValue
}
}
}
}
......@@ -321,26 +320,27 @@ RowLayout {
}
}
}
Item { width: 1; height: 1 }
QGCLabel { text: qsTr("Saved Tuning Values:") }
Column {
QGCLabel { text: qsTr("Clipboard Values:") }
GridLayout {
rows: savedRepeater.model.length
flow: GridLayout.TopToBottom
rowSpacing: _margins
columnSpacing: _margins
GridLayout {
rows: savedRepeater.model.length
flow: GridLayout.TopToBottom
rowSpacing: 0
columnSpacing: _margins
Repeater {
model: params[tuneList.indexOf(_currentTuneType)]
Repeater {
model: params[tuneList.indexOf(_currentTuneType)]
QGCLabel { text: modelData.name }
}
QGCLabel { text: modelData.name }
}
Repeater {
id: savedRepeater
Repeater {
id: savedRepeater
QGCLabel { text: modelData }
QGCLabel { text: modelData }
}
}
}
......@@ -348,12 +348,12 @@ RowLayout {
spacing: _margins
QGCButton {
text: qsTr("Save Values")
text: qsTr("Save To Clipboard")
onClicked: saveTuningParamValues()
}
QGCButton {
text: qsTr("Reset To Saved Values")
text: qsTr("Restore From Clipboard")
onClicked: resetToSavedTuningParamValues()
}
}
......@@ -372,7 +372,30 @@ RowLayout {
QGCButton {
text: dataTimer.running ? qsTr("Stop") : qsTr("Start")
onClicked: dataTimer.running = !dataTimer.running
onClicked: {
dataTimer.running = !dataTimer.running
if (autoModeChange.checked) {
_activeVehicle.flightMode = dataTimer.running ? "Stabilized" : _activeVehicle.pauseFlightMode
}
}
}
}
QGCCheckBox {
id: autoModeChange
text: qsTr("Automatic Flight Mode Switching")
}
Column {
visible: autoModeChange.checked
QGCLabel {
text: qsTr("Switches to 'Stabilized' when you click Start.")
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
text: qsTr("Switches to '%1' when you click Stop.").arg(_activeVehicle.pauseFlightMode)
font.pointSize: ScreenTools.smallFontPointSize
}
}
}
......
......@@ -489,7 +489,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
return;
}
qWarning() << "Received some bytes of terrain data: " << responseBytes.size();
qCDebug(TerrainQueryLog) << "Received some bytes of terrain data: " << responseBytes.size();
TerrainTile* terrainTile = new TerrainTile(responseBytes);
if (terrainTile->isValid()) {
......
......@@ -185,6 +185,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _lastAnnouncedLowBatteryPercent(100)
, _priorityLinkCommanded(false)
, _orbitActive(false)
, _pidTuningTelemetryMode(false)
, _pidTuningWaitingForRates(false)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
......@@ -386,6 +388,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _uid(0)
, _lastAnnouncedLowBatteryPercent(100)
, _orbitActive(false)
, _pidTuningTelemetryMode(false)
, _pidTuningWaitingForRates(false)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
......@@ -519,6 +523,8 @@ void Vehicle::_commonInit(void)
}
}
#endif
_pidTuningMessages << MAVLINK_MSG_ID_ATTITUDE << MAVLINK_MSG_ID_ATTITUDE_TARGET;
}
Vehicle::~Vehicle()
......@@ -794,7 +800,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
_handleOrbitExecutionStatus(message);
break;
case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
_handleMessageInterval(message);
break;
case MAVLINK_MSG_ID_PING:
_handlePing(link, message);
break;
......@@ -1309,13 +1317,15 @@ void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& me
// PX4 Firmware stores the first 16 characters of the git hash as binary, with the individual bytes in reverse order
_gitHash = "";
QByteArray array((char*)autopilotVersion.flight_custom_version, 8);
for (int i = 7; i >= 0; i--) {
_gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
}
} else {
// APM Firmware stores the first 8 characters of the git hash as an ASCII character string
_gitHash = QString::fromUtf8((char*)autopilotVersion.flight_custom_version, 8);
char nullStr[9];
strncpy(nullStr, (char*)autopilotVersion.flight_custom_version, 8);
nullStr[8] = 0;
_gitHash = nullStr;
}
if (_toolbox->corePlugin()->options()->checkFirmwareVersion()) {
_firmwarePlugin->checkIfIsLatestStable(this);
......@@ -3873,6 +3883,74 @@ int Vehicle::versionCompare(int major, int minor, int patch)
return _firmwarePlugin->versionCompare(this, major, minor, patch);
}
void Vehicle::_handleMessageInterval(const mavlink_message_t& message)
{
if (_pidTuningWaitingForRates) {
mavlink_message_interval_t messageInterval;
mavlink_msg_message_interval_decode(&message, &messageInterval);
int msgId = messageInterval.message_id;
if (_pidTuningMessages.contains(msgId)) {
_pidTuningMessageRatesUsecs[msgId] = messageInterval.interval_us;
}
if (_pidTuningMessageRatesUsecs.count() == _pidTuningMessages.count()) {
// We have back all the rates we requested
_pidTuningWaitingForRates = false;
_pidTuningAdjustRates(true);
}
}
}
void Vehicle::setPIDTuningTelemetryMode(bool pidTuning)
{
if (pidTuning) {
if (!_pidTuningTelemetryMode) {
// First step is to get the current message rates before we adjust them
_pidTuningTelemetryMode = true;
_pidTuningWaitingForRates = true;
_pidTuningMessageRatesUsecs.clear();
for (int telemetry: _pidTuningMessages) {
sendMavCommand(defaultComponentId(),
MAV_CMD_GET_MESSAGE_INTERVAL,
true, // show error
telemetry);
}
}
} else {
if (_pidTuningTelemetryMode) {
_pidTuningTelemetryMode = false;
if (_pidTuningWaitingForRates) {
// We never finished waiting for previous rates
_pidTuningWaitingForRates = false;
} else {
_pidTuningAdjustRates(false);
}
}
}
}
void Vehicle::_pidTuningAdjustRates(bool setRatesForTuning)
{
int requestedRate = (int)(1000000.0 / 30.0); // 30 Hz in usecs
for (int telemetry: _pidTuningMessages) {
if (requestedRate < _pidTuningMessageRatesUsecs[telemetry]) {
sendMavCommand(defaultComponentId(),
MAV_CMD_SET_MESSAGE_INTERVAL,
true, // show error
telemetry,
setRatesForTuning ? requestedRate : _pidTuningMessageRatesUsecs[telemetry]);
}
}
setLiveUpdates(setRatesForTuning);
_setpointFactGroup.setLiveUpdates(setRatesForTuning);
}
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::flashBootloader(void)
{
......
......@@ -758,6 +758,8 @@ public:
/// @param percent 0-no power, 100-full power
Q_INVOKABLE void motorTest(int motor, int percent);
Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);
#if !defined(NO_ARDUPILOT_DIALECT)
Q_INVOKABLE void flashBootloader(void);
#endif
......@@ -1265,6 +1267,7 @@ private:
void _handleEstimatorStatus(mavlink_message_t& message);
void _handleStatusText(mavlink_message_t& message, bool longVersion);
void _handleOrbitExecutionStatus(const mavlink_message_t& message);
void _handleMessageInterval(const mavlink_message_t& message);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message);
......@@ -1291,6 +1294,7 @@ private:
void _setCapabilities(uint64_t capabilityBits);
void _updateArmed(bool armed);
bool _apmArmingNotRequired(void);
void _pidTuningAdjustRates(bool setRatesForTuning);
int _id; ///< Mavlink system id
int _defaultComponentId;
......@@ -1473,6 +1477,12 @@ private:
QTimer _orbitTelemetryTimer;
static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive
// PID Tuning telemetry mode
bool _pidTuningTelemetryMode;
bool _pidTuningWaitingForRates;
QList<int> _pidTuningMessages;
QMap<int, int> _pidTuningMessageRatesUsecs;
// FactGroup facts
Fact _rollFact;
......
......@@ -14,6 +14,7 @@
#include <QFileInfo>
#include <QtEndian>
#include <QSignalSpy>
const char* LogReplayLinkConfiguration::_logFilenameKey = "logFilename";
......@@ -368,7 +369,7 @@ void LogReplayLink::_readNextLogEntry(void)
timeToNextExecutionMSecs = desiredPacedTimeMSecs - currentTimeMSecs;
}
emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
_signalCurrentLogTimeSecs();
// And schedule the next execution of this function.
_readTickTimer.start(timeToNextExecutionMSecs);
......@@ -450,8 +451,12 @@ void LogReplayLink::_resetPlaybackToBeginning(void)
void LogReplayLink::movePlayhead(int percentComplete)
{
if (isPlaying()) {
qWarning() << "Should not move playhead while playing, pause first";
return;
_pauseOnThread();
QSignalSpy waitForPause(this, SIGNAL(playbackPaused));
waitForPause.wait();
if (_readTickTimer.isActive()) {
return;
}
}
if (percentComplete < 0 || percentComplete > 100) {
......@@ -495,7 +500,8 @@ void LogReplayLink::movePlayhead(int percentComplete)
// And scan until we reach the start of a MAVLink message. We make sure to record this timestamp for
// smooth jumping around the file.
_logCurrentTimeUSecs = _seekToNextMavlinkMessage(&dummy);
_signalCurrentLogTimeSecs();
// Now update the UI with our actual final position.
newRelativeTimeUSecs = (float)(_logCurrentTimeUSecs - _logStartTimeUSecs);
percentComplete = (newRelativeTimeUSecs / _logDurationUSecs) * 100;
......@@ -561,3 +567,8 @@ void LogReplayLink::_playbackError(void)
_logFile.close();
emit playbackError();
}
void LogReplayLink::_signalCurrentLogTimeSecs(void)
{
emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
}
......@@ -120,6 +120,7 @@ private:
void _finishPlayback(void);
void _playbackError(void);
void _resetPlaybackToBeginning(void);
void _signalCurrentLogTimeSecs(void);
// Virtuals from LinkInterface
virtual bool _connect(void);
......
......@@ -271,7 +271,7 @@ void MainWindow::_buildCommonWidgets(void)
// Log player
// TODO: Make this optional with a preferences setting or under a "View" menu
logPlayer = new QGCMAVLinkLogPlayer(statusBar());
statusBar()->addPermanentWidget(logPlayer);
statusBar()->addPermanentWidget(logPlayer, 1);
// Populate widget menu
for (int i = 0, end = ARRAY_SIZE(rgDockWidgetNames); i < end; i++) {
......
......@@ -142,7 +142,6 @@ void QGCMAVLinkLogPlayer::_playbackStarted(void)
_enablePlaybackControls(true);
_ui->playButton->setChecked(true);
_ui->playButton->setIcon(QIcon(":/res/Pause"));
_ui->positionSlider->setEnabled(false);
}
/// Signalled from LogReplayLink when replay is paused
......@@ -150,7 +149,6 @@ void QGCMAVLinkLogPlayer::_playbackPaused(void)
{
_ui->playButton->setIcon(QIcon(":/res/Play"));
_ui->playButton->setChecked(false);
_ui->positionSlider->setEnabled(true);
}
void QGCMAVLinkLogPlayer::_playbackPercentCompleteChanged(int percentComplete)
......
......@@ -75,7 +75,7 @@
<number>100</number>
</property>
<property name="tracking">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment