Commit 81e44f00 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into foo

# Conflicts:
#	src/QmlControls/PIDTuning.qml
#	src/ui/MainWindow.cc
parents 0e7f614d df6e1a51
......@@ -6,6 +6,8 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* 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
......
......@@ -76,6 +76,7 @@ public class QGCActivity extends QtActivity
private static final String ACTION_USB_PERMISSION = "org.mavlink.qgroundcontrol.action.USB_PERMISSION";
private static PendingIntent _usbPermissionIntent = null;
private TaiSync taiSync = null;
private Timer probeAccessoriesTimer = null;
public static Context m_context;
......@@ -225,7 +226,15 @@ public class QGCActivity extends QtActivity
IntentFilter accessoryFilter = new IntentFilter(ACTION_USB_PERMISSION);
filter.addAction(UsbManager.ACTION_USB_ACCESSORY_DETACHED);
registerReceiver(mOpenAccessoryReceiver, accessoryFilter);
probeAccessories();
probeAccessoriesTimer = new Timer();
probeAccessoriesTimer.schedule(new TimerTask() {
@Override
public void run()
{
probeAccessories();
}
}, 0, 3000);
} catch(Exception e) {
Log.e(TAG, "Exception: " + e);
}
......@@ -243,6 +252,9 @@ public class QGCActivity extends QtActivity
@Override
protected void onDestroy()
{
if (probeAccessoriesTimer != null) {
probeAccessoriesTimer.cancel();
}
unregisterReceiver(mOpenAccessoryReceiver);
try {
if(_wakeLock != null) {
......@@ -706,22 +718,26 @@ public class QGCActivity extends QtActivity
}
}
Object probeAccessoriesLock = new Object();
private void probeAccessories()
{
final PendingIntent pendingIntent = PendingIntent.getBroadcast(this, 0, new Intent(ACTION_USB_PERMISSION), 0);
new Thread(new Runnable() {
public void run() {
Log.i(TAG, "probeAccessories");
UsbAccessory[] accessories = _usbManager.getAccessoryList();
if (accessories != null) {
for (UsbAccessory usbAccessory : accessories) {
if (_usbManager.hasPermission(usbAccessory)) {
openAccessory(usbAccessory);
} else {
Log.i(TAG, "requestPermission");
_usbManager.requestPermission(usbAccessory, pendingIntent);
synchronized(openAccessoryLock) {
Log.i(TAG, "probeAccessories");
UsbAccessory[] accessories = _usbManager.getAccessoryList();
if (accessories != null) {
for (UsbAccessory usbAccessory : accessories) {
if (_usbManager.hasPermission(usbAccessory)) {
openAccessory(usbAccessory);
} else {
Log.i(TAG, "requestPermission");
_usbManager.requestPermission(usbAccessory, pendingIntent);
}
}
}
}
}
}
}).start();
......
......@@ -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"));
}
}
......
......@@ -14,13 +14,50 @@
#include <QVariant>
#include <QQmlProperty>
bool APMFlightModesComponentController::_typeRegistered = false;
const char* APMFlightModesComponentController::_simpleParamName = "SIMPLE";
const char* APMFlightModesComponentController::_superSimpleParamName = "SUPER_SIMPLE";
APMFlightModesComponentController::APMFlightModesComponentController(void)
: _activeFlightMode(0)
, _channelCount(Vehicle::cMaxRcChannels)
: _activeFlightMode (0)
, _channelCount (Vehicle::cMaxRcChannels)
, _simpleMode (SimpleModeStandard)
, _simpleModeFact (parameterExists(-1, _simpleParamName) ? getParameterFact(-1, _simpleParamName) : nullptr)
, _superSimpleModeFact (parameterExists(-1, _superSimpleParamName) ? getParameterFact(-1, _superSimpleParamName) : nullptr)
, _simpleModesSupported (_simpleModeFact && _superSimpleModeFact)
{
if (!_typeRegistered) {
qmlRegisterUncreatableType<APMFlightModesComponentController>("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController", "Reference only");
}
_modeParamPrefix = _vehicle->rover() ? QStringLiteral("MODE") : QStringLiteral("FLTMODE");
_modeChannelParam = _vehicle->rover() ? QStringLiteral("MODE_CH") : QStringLiteral("FLTMODE_CH");
_simpleModeNames << tr("Off") << tr("Simple") << tr("Super-Simple") << tr("Custom");
for (int i=0; i<_cFltModes; i++) {
_simpleModeEnabled.append(QVariant(false));
_superSimpleModeEnabled.append(QVariant(false));
}
if (_simpleModesSupported) {
_setupSimpleModeEnabled();
uint8_t simpleModeValue = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt());
uint8_t superSimpleModeValue = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt());
if (simpleModeValue == 0 && superSimpleModeValue == 0) {
_simpleMode = SimpleModeStandard;
} else if (simpleModeValue == _allSimpleBits && superSimpleModeValue == 0) {
_simpleMode = SimpleModeSimple;
} else if (simpleModeValue == 0 && superSimpleModeValue == _allSimpleBits) {
_simpleMode = SimpleModeSuperSimple;
} else {
_simpleMode = SimpleModeCustom;
}
connect(this, &APMFlightModesComponentController::simpleModeChanged, this, &APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode);
}
QStringList usedParams;
for (int i=1; i<7; i++) {
usedParams << QStringLiteral("%1%2").arg(_modeParamPrefix).arg(i);
......@@ -29,8 +66,10 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
return;
}
_rgChannelOptionEnabled << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false);
for (int i=0; i<_cChannelOptions; i++) {
_rgChannelOptionEnabled.append(QVariant(false));
}
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged);
}
......@@ -65,7 +104,7 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int
}
emit activeFlightModeChanged(_activeFlightMode);
for (int i=0; i<6; i++) {
for (int i=0; i<_cChannelOptions; i++) {
_rgChannelOptionEnabled[i] = QVariant(false);
channelValue = pwmValues[i+6];
if (channelValue > 1800) {
......@@ -74,3 +113,66 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int
}
emit channelOptionEnabledChanged();
}
void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void)
{
int newSimpleModeValue = 0;
int newSuperSimpleModeValue = 0;
if (_simpleMode == SimpleModeSimple) {
newSimpleModeValue = _allSimpleBits;
} else if (_simpleMode == SimpleModeSuperSimple) {
newSuperSimpleModeValue = _allSimpleBits;
}
for (int i=0; i<_cFltModes; i++) {
_simpleModeEnabled[i] = false;
_superSimpleModeEnabled[i] = false;
}
emit simpleModeEnabledChanged();
emit superSimpleModeEnabledChanged();
_simpleModeFact->setRawValue(newSimpleModeValue);
_superSimpleModeFact->setRawValue(newSuperSimpleModeValue);
}
void APMFlightModesComponentController::setSimpleMode(int fltModeIndex, bool enabled)
{
if (fltModeIndex < _cFltModes) {
uint8_t mode = static_cast<uint8_t>(_simpleModeFact->rawValue().toInt());
if (enabled) {
mode |= 1 << fltModeIndex;
} else {
mode &= ~(1 << fltModeIndex);
}
_simpleModeFact->setRawValue(mode);
}
}
void APMFlightModesComponentController::setSuperSimpleMode(int fltModeIndex, bool enabled)
{
if (fltModeIndex < _cFltModes) {
uint8_t mode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toInt());
if (enabled) {
mode |= 1 << fltModeIndex;
} else {
mode &= ~(1 << fltModeIndex);
}
_superSimpleModeFact->setRawValue(mode);
}
}
void APMFlightModesComponentController::_setupSimpleModeEnabled(void)
{
uint8_t simpleMode = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt());
uint8_t superSimpleMode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt());
for (int i=0; i<_cFltModes; i++) {
uint8_t bitSet = static_cast<uint8_t>(1 << i);
_simpleModeEnabled[i] = !!(simpleMode & bitSet);
_superSimpleModeEnabled[i] = !!(superSimpleMode & bitSet);
}
emit simpleModeEnabledChanged();
emit superSimpleModeEnabledChanged();
}
......@@ -27,30 +27,68 @@ class APMFlightModesComponentController : public FactPanelController
Q_OBJECT
public:
enum SimpleModeValues {
SimpleModeStandard = 0,
SimpleModeSimple,
SimpleModeSuperSimple,
SimpleModeCustom
};
Q_ENUM(SimpleModeValues)
APMFlightModesComponentController(void);
Q_PROPERTY(QString modeParamPrefix MEMBER _modeParamPrefix CONSTANT)
Q_PROPERTY(QString modeChannelParam MEMBER _modeChannelParam CONSTANT)
Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged)
Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT)
Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged)
Q_PROPERTY(QString modeParamPrefix MEMBER _modeParamPrefix CONSTANT)
Q_PROPERTY(QString modeChannelParam MEMBER _modeChannelParam CONSTANT)
Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged)
Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT)
Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged)
Q_PROPERTY(bool simpleModesSupported MEMBER _simpleModesSupported CONSTANT)
Q_PROPERTY(QStringList simpleModeNames MEMBER _simpleModeNames CONSTANT)
Q_PROPERTY(int simpleMode MEMBER _simpleMode NOTIFY simpleModeChanged)
Q_PROPERTY(QVariantList simpleModeEnabled MEMBER _simpleModeEnabled NOTIFY simpleModeEnabledChanged)
Q_PROPERTY(QVariantList superSimpleModeEnabled MEMBER _superSimpleModeEnabled NOTIFY superSimpleModeEnabledChanged)
Q_INVOKABLE void setSimpleMode(int fltModeIndex, bool enabled);
Q_INVOKABLE void setSuperSimpleMode(int fltModeIndex, bool enabled);
int activeFlightMode(void) const { return _activeFlightMode; }
QVariantList channelOptionEnabled(void) const { return _rgChannelOptionEnabled; }
signals:
void activeFlightModeChanged(int activeFlightMode);
void channelOptionEnabledChanged(void);
void activeFlightModeChanged (int activeFlightMode);
void channelOptionEnabledChanged (void);
void simpleModeChanged (int simpleMode);
void simpleModeEnabledChanged (void);
void superSimpleModeEnabledChanged (void);
private slots:
void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
void _rcChannelsChanged (int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
void _updateSimpleParamsFromSimpleMode (void);
void _setupSimpleModeEnabled (void);
private:
QString _modeParamPrefix;
QString _modeChannelParam;
int _activeFlightMode;
int _channelCount;
QVariantList _rgChannelOptionEnabled;
QStringList _simpleModeNames;
int _simpleMode;
Fact* _simpleModeFact;
Fact* _superSimpleModeFact;
bool _simpleModesSupported;
QVariantList _simpleModeEnabled;
QVariantList _superSimpleModeEnabled;
static const uint8_t _allSimpleBits = 0x3F;
static const int _cChannelOptions = 10;
static const int _cSimpleModeBits = 8;
static const int _cFltModes = 6;
static const char* _simpleParamName;
static const char* _superSimpleParamName;
static bool _typeRegistered;
};
#endif
......@@ -515,7 +515,7 @@ SetupPage {
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new voltage multiplier.")
text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new adjusted voltage multiplier.")
}
Grid {
......@@ -536,7 +536,7 @@ SetupPage {
}
QGCButton {
text: "Calculate"
text: qsTr("Calculate And Set")
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
......@@ -598,7 +598,7 @@ SetupPage {
}
QGCButton {
text: "Calculate"
text: qsTr("Calculate And Set")
onClicked: {
var measuredCurrentValue = parseFloat(measuredCurrent.text)
......
......@@ -692,16 +692,25 @@ SetupPage {
calValid: controller.orientationCalDownSideDone
calInProgress: controller.orientationCalDownSideInProgress
calInProgressText: controller.orientationCalDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: controller.orientationCalDownSideRotate ? "qrc:///qmlimages/VehicleDownRotate.png" : "qrc:///qmlimages/VehicleDown.png"
imageSource: "qrc:///qmlimages/VehicleDown.png"
}
VehicleRotationCal {
width: parent.indicatorWidth
height: parent.indicatorHeight
visible: controller.orientationCalUpsideDownSideVisible
calValid: controller.orientationCalUpsideDownSideDone
calInProgress: controller.orientationCalUpsideDownSideInProgress
calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: controller.orientationCalUpsideDownSideRotate ? "qrc:///qmlimages/VehicleUpsideDownRotate.png" : "qrc:///qmlimages/VehicleUpsideDown.png"
visible: controller.orientationCalLeftSideVisible
calValid: controller.orientationCalLeftSideDone
calInProgress: controller.orientationCalLeftSideInProgress
calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: "qrc:///qmlimages/VehicleLeft.png"
}
VehicleRotationCal {
width: parent.indicatorWidth
height: parent.indicatorHeight
visible: controller.orientationCalRightSideVisible
calValid: controller.orientationCalRightSideDone
calInProgress: controller.orientationCalRightSideInProgress
calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: "qrc:///qmlimages/VehicleRight.png"
}
VehicleRotationCal {
width: parent.indicatorWidth
......@@ -710,7 +719,7 @@ SetupPage {
calValid: controller.orientationCalNoseDownSideDone
calInProgress: controller.orientationCalNoseDownSideInProgress
calInProgressText: controller.orientationCalNoseDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: controller.orientationCalNoseDownSideRotate ? "qrc:///qmlimages/VehicleNoseDownRotate.png" : "qrc:///qmlimages/VehicleNoseDown.png"
imageSource: "qrc:///qmlimages/VehicleNoseDown.png"
}
VehicleRotationCal {
width: parent.indicatorWidth
......@@ -719,25 +728,16 @@ SetupPage {
calValid: controller.orientationCalTailDownSideDone
calInProgress: controller.orientationCalTailDownSideInProgress
calInProgressText: controller.orientationCalTailDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: controller.orientationCalTailDownSideRotate ? "qrc:///qmlimages/VehicleTailDownRotate.png" : "qrc:///qmlimages/VehicleTailDown.png"
imageSource: "qrc:///qmlimages/VehicleTailDown.png"
}
VehicleRotationCal {
width: parent.indicatorWidth
height: parent.indicatorHeight
visible: controller.orientationCalLeftSideVisible
calValid: controller.orientationCalLeftSideDone
calInProgress: controller.orientationCalLeftSideInProgress
calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: controller.orientationCalLeftSideRotate ? "qrc:///qmlimages/VehicleLeftRotate.png" : "qrc:///qmlimages/VehicleLeft.png"
}
VehicleRotationCal {
width: parent.indicatorWidth
height: parent.indicatorHeight
visible: controller.orientationCalRightSideVisible
calValid: controller.orientationCalRightSideDone
calInProgress: controller.orientationCalRightSideInProgress
calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: controller.orientationCalRightSideRotate ? "qrc:///qmlimages/VehicleRightRotate.png" : "qrc:///qmlimages/VehicleRight.png"
visible: controller.orientationCalUpsideDownSideVisible
calValid: controller.orientationCalUpsideDownSideDone
calInProgress: controller.orientationCalUpsideDownSideInProgress
calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
imageSource: "qrc:///qmlimages/VehicleUpsideDown.png"
}
}
}
......
......@@ -227,7 +227,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone
_startLogCalibration();
uint8_t compassBits = 0;
if (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_DEV_ID"))->rawValue().toInt() > 0 &&
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE"))->rawValue().toBool()) {
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE"))->rawValue().toBool()) {
compassBits |= 1 << 0;
qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 1";
} else {
......@@ -236,7 +236,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone
_rgCompassCalFitness[0] = 0;
}
if (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_DEV_ID2"))->rawValue().toInt() > 0 &&
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE2"))->rawValue().toBool()) {
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE2"))->rawValue().toBool()) {
compassBits |= 1 << 1;
qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 2";
} else {
......@@ -245,7 +245,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone
_rgCompassCalFitness[1] = 0;
}
if (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_DEV_ID3"))->rawValue().toInt() > 0 &&
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE3"))->rawValue().toBool()) {
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE3"))->rawValue().toBool()) {
compassBits |= 1 << 2;
qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 3";
} else {
......@@ -335,11 +335,118 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
return;
}
if (text.startsWith(QLatin1Literal("PreArm:")) || text.startsWith(QLatin1Literal("EKF"))
|| text.startsWith(QLatin1Literal("Arm")) || text.startsWith(QLatin1Literal("Initialising"))) {
QString originalMessageText = text;
text = text.toLower();
QStringList hidePrefixList = { QStringLiteral("prearm:"), QStringLiteral("ekf"), QStringLiteral("arm"), QStringLiteral("initialising") };
for (const QString& hidePrefix: hidePrefixList) {
if (text.startsWith(hidePrefix)) {
return;
}
}
if (_calTypeInProgress == CalTypeAccel) {
if (text == QStringLiteral("place vehicle level and press any key.")) {
_startVisualCalibration();
_cancelButton->setEnabled(false);
// Reset all progress indication
_orientationCalDownSideDone = false;
_orientationCalUpsideDownSideDone = false;
_orientationCalLeftSideDone = false;
_orientationCalRightSideDone = false;
_orientationCalTailDownSideDone = false;
_orientationCalNoseDownSideDone = false;
_orientationCalDownSideInProgress = false;
_orientationCalUpsideDownSideInProgress = false;
_orientationCalLeftSideInProgress = false;
_orientationCalRightSideInProgress = false;
_orientationCalNoseDownSideInProgress = false;
_orientationCalTailDownSideInProgress = false;
// Reset all visibility
_orientationCalDownSideVisible = false;
_orientationCalUpsideDownSideVisible = false;
_orientationCalLeftSideVisible = false;
_orientationCalRightSideVisible = false;
_orientationCalTailDownSideVisible = false;
_orientationCalNoseDownSideVisible = false;
_calTypeInProgress = CalTypeAccel;
_orientationCalDownSideVisible = true;
_orientationCalUpsideDownSideVisible = true;
_orientationCalLeftSideVisible = true;
_orientationCalRightSideVisible = true;
_orientationCalTailDownSideVisible = true;
_orientationCalNoseDownSideVisible = true;
emit orientationCalSidesDoneChanged();
emit orientationCalSidesVisibleChanged();
emit orientationCalSidesInProgressChanged();
_updateAndEmitShowOrientationCalArea(true);
}
QString placeVehicle("place vehicle ");
if (_calTypeInProgress == CalTypeAccel && text.startsWith(placeVehicle)) {
text = text.right(text.length() - placeVehicle.length());
if (text.startsWith("level")) {
_orientationCalDownSideInProgress = true;
_nextButton->setEnabled(true);
} else if (text.startsWith("on its left")) {
_orientationCalDownSideDone = true;
_orientationCalDownSideInProgress = false;
_orientationCalLeftSideInProgress = true;
_progressBar->setProperty("value", (qreal)(17 / 100.0));
} else if (text.startsWith("on its right")) {
_orientationCalLeftSideDone = true;
_orientationCalLeftSideInProgress = false;
_orientationCalRightSideInProgress = true;
_progressBar->setProperty("value", (qreal)(34 / 100.0));
} else if (text.startsWith("nose down")) {
_orientationCalRightSideDone = true;
_orientationCalRightSideInProgress = false;
_orientationCalNoseDownSideInProgress = true;
_progressBar->setProperty("value", (qreal)(51 / 100.0));
} else if (text.startsWith("nose up")) {
_orientationCalNoseDownSideDone = true;
_orientationCalNoseDownSideInProgress = false;
_orientationCalTailDownSideInProgress = true;
_progressBar->setProperty("value", (qreal)(68 / 100.0));
} else if (text.startsWith("on its back")) {
_orientationCalTailDownSideDone = true;
_orientationCalTailDownSideInProgress = false;
_orientationCalUpsideDownSideInProgress = true;
_progressBar->setProperty("value", (qreal)(85 / 100.0));
}
_orientationCalAreaHelpText->setProperty("text", tr("Hold still in the current orientation and press Next when ready"));
emit orientationCalSidesDoneChanged();
emit orientationCalSidesInProgressChanged();
emit orientationCalSidesRotateChanged();
}
}
_appendStatusLog(originalMessageText);
qCDebug(APMSensorsComponentControllerLog) << originalMessageText << severity;
if (text.contains(QLatin1String("calibration successful"))) {
_stopCalibration(StopCalibrationSuccess);
return;
}
if (text.startsWith(QStringLiteral("calibration cancelled"))) {
_stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
return;
}
if (text.startsWith(QStringLiteral("calibration failed"))) {
_stopCalibration(StopCalibrationFailed);
return;
}
#if 0
if (text.contains(QLatin1Literal("progress <"))) {
QString percent = text.split("<").last().split(">").first();
bool ok;
......@@ -533,6 +640,7 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
_stopCalibration(StopCalibrationFailed);
return;
}
#endif
}
void APMSensorsComponentController::_refreshParams(void)
......
......@@ -59,26 +59,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
}
*/
}
}
......
......@@ -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(); }
......
......@@ -4311,7 +4311,7 @@ default 1.5 turns per second</short_desc>
<long_desc>This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.</long_desc>
<boolean />
</parameter>
<parameter default="30." name="MC_DTERM_CUTOFF" type="FLOAT">
<parameter default="0." name="MC_DTERM_CUTOFF" type="FLOAT">
<short_desc>Cutoff frequency for the low pass filter on the D-term in the rate controller</short_desc>
<long_desc>The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to decrease the driver-level filtering, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.</long_desc>
<min>0</min>
......@@ -8352,7 +8352,7 @@ is less than 50% of this value</short_desc>
<unit>Hz</unit>
<reboot_required>true</reboot_required>
</parameter>
<parameter default="80.0" name="IMU_GYRO_CUTOFF" type="FLOAT">
<parameter default="30.0" name="IMU_GYRO_CUTOFF" type="FLOAT">
<short_desc>Driver level cutoff frequency for gyro</short_desc>
<long_desc>The cutoff frequency for the 2nd order butterworth filter on the gyro driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.</long_desc>
<min>0</min>
......
......@@ -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;