Browse Source

Merge pull request #6956 from mavlink/androidCrashFix

Android crash fix
QGC4.4
Gus Grubba 7 years ago committed by GitHub
parent
commit
a9a570dd97
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 12
      src/QGCApplication.cc
  2. 2
      src/comm/MAVLinkProtocol.cc
  3. 4
      src/comm/MAVLinkProtocol.h
  4. 2
      src/ui/preferences/GeneralSettings.qml

12
src/QGCApplication.cc

@ -669,7 +669,9 @@ void QGCApplication::_missingParamsDisplay(void)
QObject* QGCApplication::_rootQmlObject() QObject* QGCApplication::_rootQmlObject()
{ {
#ifdef __mobile__ #ifdef __mobile__
return _qmlAppEngine->rootObjects()[0]; if(_qmlAppEngine && _qmlAppEngine->rootObjects().size())
return _qmlAppEngine->rootObjects()[0];
return nullptr;
#else #else
MainWindow * mainWindow = MainWindow::instance(); MainWindow * mainWindow = MainWindow::instance();
if (mainWindow) { if (mainWindow) {
@ -711,12 +713,16 @@ void QGCApplication::showMessage(const QString& message)
void QGCApplication::showSetupView(void) void QGCApplication::showSetupView(void)
{ {
QMetaObject::invokeMethod(_rootQmlObject(), "showSetupView"); if(_rootQmlObject()) {
QMetaObject::invokeMethod(_rootQmlObject(), "showSetupView");
}
} }
void QGCApplication::qmlAttemptWindowClose(void) void QGCApplication::qmlAttemptWindowClose(void)
{ {
QMetaObject::invokeMethod(_rootQmlObject(), "attemptWindowClose"); if(_rootQmlObject()) {
QMetaObject::invokeMethod(_rootQmlObject(), "attemptWindowClose");
}
} }
bool QGCApplication::isInternetAvailable() bool QGCApplication::isInternetAvailable()

2
src/comm/MAVLinkProtocol.cc

@ -68,6 +68,8 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
memset(totalLossCounter, 0, sizeof(totalLossCounter)); memset(totalLossCounter, 0, sizeof(totalLossCounter));
memset(runningLossPercent, 0, sizeof(runningLossPercent)); memset(runningLossPercent, 0, sizeof(runningLossPercent));
memset(firstMessage, 1, sizeof(firstMessage)); memset(firstMessage, 1, sizeof(firstMessage));
memset(&_status, 0, sizeof(_status));
memset(&_message, 0, sizeof(_message));
} }
MAVLinkProtocol::~MAVLinkProtocol() MAVLinkProtocol::~MAVLinkProtocol()

4
src/comm/MAVLinkProtocol.h

@ -108,8 +108,8 @@ protected:
uint64_t totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total messages lost during transmission. uint64_t totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total messages lost during transmission.
float runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]; ///< Loss rate float runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]; ///< Loss rate
mavlink_message_t _message = {}; mavlink_message_t _message;
mavlink_status_t _status = {}; mavlink_status_t _status;
bool versionMismatchIgnore; bool versionMismatchIgnore;
int systemId; int systemId;

2
src/ui/preferences/GeneralSettings.qml

@ -504,7 +504,7 @@ QGCView {
Item { width: rtkGrid.firstColWidth; height: 1 } Item { width: rtkGrid.firstColWidth; height: 1 }
QGCButton { QGCButton {
text: qsTr("Save Current Base Position") text: qsTr("Save Current Base Position")
enabled: QGroundControl.gpsRtk.valid.value enabled: QGroundControl.gpsRtk && QGroundControl.gpsRtk.valid.value
Layout.columnSpan: 2 Layout.columnSpan: 2
onClicked: { onClicked: {

Loading…
Cancel
Save