Commit daa2502a authored by Gus Grubba's avatar Gus Grubba

Updating MAVLink

Fixed inverse logic in camera parameter retry count
Skip close timeout if not Windows
parent 94504df9
Subproject commit 646c3f4eeae648ffb2cc7dca041d414c4b42c88a
Subproject commit 8aea2f7207f37841ede0a01d79724bfd03caf99c
......@@ -187,7 +187,7 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
_paramWriteTimer.start();
} else {
if(ack.param_result == PARAM_ACK_FAILED) {
if(++_sentRetries > 3) {
if(++_sentRetries < 3) {
//-- Try again
qCWarning(CameraIOLog) << "Param set failed:" << _fact->name() << _sentRetries;
_paramWriteTimer.start();
......
......@@ -56,6 +56,7 @@ Item {
property bool isAndroid: ScreenToolsController.isAndroid
property bool isiOS: ScreenToolsController.isiOS
property bool isMobile: ScreenToolsController.isMobile
property bool isWindows: ScreenToolsController.isWindows
property bool isDebug: ScreenToolsController.isDebug
property bool isTinyScreen: (Screen.width / Screen.pixelDensity) < 120 // 120mm
property bool isShortScreen: ScreenToolsController.isMobile && ((Screen.height / Screen.width) < 0.6) // Nexus 7 for example
......
......@@ -36,6 +36,7 @@ public:
Q_PROPERTY(bool isDebug READ isDebug CONSTANT)
Q_PROPERTY(bool isMacOS READ isMacOS CONSTANT)
Q_PROPERTY(bool isLinux READ isLinux CONSTANT)
Q_PROPERTY(bool isWindows READ isWindows CONSTANT)
Q_PROPERTY(QString iOSDevice READ iOSDevice CONSTANT)
Q_PROPERTY(QString fixedFontFamily READ fixedFontFamily CONSTANT)
......@@ -54,26 +55,37 @@ public:
bool isiOS () { return false; }
bool isLinux () { return false; }
bool isMacOS () { return false; }
bool isWindows () { return false; }
#elif defined(__ios__)
bool isAndroid () { return false; }
bool isiOS () { return true; }
bool isLinux () { return false; }
bool isMacOS () { return false; }
bool isWindows () { return false; }
#elif defined(__macos__)
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isLinux () { return false; }
bool isMacOS () { return true; }
bool isWindows () { return false; }
#elif defined(Q_OS_LINUX)
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isLinux () { return true; }
bool isMacOS () { return false; }
bool isWindows () { return false; }
#elif defined(Q_OS_WIN)
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isLinux () { return false; }
bool isMacOS () { return false; }
bool isWindows () { return true; }
#else
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isLinux () { return false; }
bool isMacOS () { return false; }
bool isWindows () { return false; }
#endif
#ifdef QT_DEBUG
......
......@@ -141,7 +141,11 @@ Item {
// The above shutdown causes a flurry of activity as the vehicle components are removed. This in turn
// causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent
// the crash, we ignore the close event and setup a delayed timer to close the window after things settle down.
delayedWindowCloseTimer.start()
if(ScreenTools.isWindows) {
delayedWindowCloseTimer.start()
} else {
mainWindow.reallyClose()
}
}
MessageDialog {
......
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