diff --git a/src/AnalyzeView/MavlinkConsoleController.cc b/src/AnalyzeView/MavlinkConsoleController.cc index 072d89c209e924c7020f92ca526f21efc1c5bb22..03e85b655e4563454f556083c924be420549bbc5 100644 --- a/src/AnalyzeView/MavlinkConsoleController.cc +++ b/src/AnalyzeView/MavlinkConsoleController.cc @@ -80,9 +80,10 @@ MavlinkConsoleController::_receiveData(uint8_t device, uint8_t, uint16_t, uint32 void MavlinkConsoleController::_sendSerialData(QByteArray data, bool close) { - Q_ASSERT(_vehicle); - if (!_vehicle) + if (!_vehicle) { + qWarning() << "Internal error"; return; + } // Send maximum sized chunks until the complete buffer is transmitted while(data.size()) { diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 4f938d0f984b9c11b0e8d67a5ad0237184c154c9..666734cd92aa0adf85cbe69dcd5f3a1884a032d7 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -21,7 +21,7 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : QObject(parent) , _vehicle(vehicle) , _firmwarePlugin(vehicle->firmwarePlugin()) - , _setupComplete(false) + , _setupComplete(false) { } @@ -33,27 +33,29 @@ AutoPilotPlugin::~AutoPilotPlugin() void AutoPilotPlugin::_recalcSetupComplete(void) { - bool newSetupComplete = true; - - foreach(const QVariant componentVariant, vehicleComponents()) { - VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); - Q_ASSERT(component); - - if (!component->setupComplete()) { - newSetupComplete = false; - break; - } - } - - if (_setupComplete != newSetupComplete) { - _setupComplete = newSetupComplete; - emit setupCompleteChanged(_setupComplete); - } + bool newSetupComplete = true; + + foreach(const QVariant componentVariant, vehicleComponents()) { + VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); + if (component) { + if (!component->setupComplete()) { + newSetupComplete = false; + break; + } + } else { + qWarning() << "AutoPilotPlugin::_recalcSetupComplete Incorrectly typed VehicleComponent"; + } + } + + if (_setupComplete != newSetupComplete) { + _setupComplete = newSetupComplete; + emit setupCompleteChanged(_setupComplete); + } } bool AutoPilotPlugin::setupComplete(void) { - return _setupComplete; + return _setupComplete; } void AutoPilotPlugin::parametersReadyPreChecks(void) diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc index d4be51de55a2fcaf318230ddce577c1370debc32..78b84a4b33ff936c1d8f7776f35fe2d55a803309 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc @@ -16,7 +16,9 @@ GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : AutoPilotPlugin(vehicle, parent) { - Q_ASSERT(vehicle); + if (!vehicle) { + qWarning() << "Internal error"; + } } const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.cc b/src/AutoPilotPlugins/PX4/AirframeComponent.cc index bb7ae98e9ff68fd1ca4a10ec422867798b7cadf8..67b356c859cfc91d573a32b5b088d128f53417f5 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.cc @@ -15,96 +15,11 @@ #include "QGCQmlWidgetHolder.h" #include "ParameterManager.h" -#if 0 -// Broken by latest mavlink module changes. Not used yet. Comment out for now. -// Discussing mavlink fix. -struct mavType { - int type; - const char* description; -}; - -/// @brief Used to translate from MAV_TYPE_* id to user string -static const struct mavType mavTypeInfo[] = { - { MAV_TYPE_GENERIC, "Generic" }, - { MAV_TYPE_FIXED_WING, "Fixed Wing" }, - { MAV_TYPE_QUADROTOR, "Quadrotor" }, - { MAV_TYPE_COAXIAL, "Coaxial" }, - { MAV_TYPE_HELICOPTER, "Helicopter"}, - { MAV_TYPE_ANTENNA_TRACKER, "Antenna Tracker" }, - { MAV_TYPE_GCS, "Ground Control Station" }, - { MAV_TYPE_AIRSHIP, "Airship" }, - { MAV_TYPE_FREE_BALLOON, "Free Balloon" }, - { MAV_TYPE_ROCKET, "Rocket" }, - { MAV_TYPE_GROUND_ROVER, "Ground Rover" }, - { MAV_TYPE_SURFACE_BOAT, "Boat" }, - { MAV_TYPE_SUBMARINE, "Submarine" }, - { MAV_TYPE_HEXAROTOR, "Hexarotor" }, - { MAV_TYPE_OCTOROTOR, "Octorotor" }, - { MAV_TYPE_TRICOPTER, "Tricopter" }, - { MAV_TYPE_FLAPPING_WING, "Flapping Wing" }, - { MAV_TYPE_KITE, "Kite" }, - { MAV_TYPE_ONBOARD_CONTROLLER, "Onbard companion controller" }, - { MAV_TYPE_VTOL_DUOROTOR, "Two-rotor VTOL" }, - { MAV_TYPE_VTOL_QUADROTOR, "Quad-rotor VTOL" }, - { MAV_TYPE_VTOL_RESERVED1, "Reserved" }, - { MAV_TYPE_VTOL_RESERVED2, "Reserved" }, - { MAV_TYPE_VTOL_RESERVED3, "Reserved" }, - { MAV_TYPE_VTOL_RESERVED4, "Reserved" }, - { MAV_TYPE_VTOL_RESERVED5, "Reserved" }, - { MAV_TYPE_GIMBAL, "Gimbal" }, -}; -static size_t cMavTypes = sizeof(mavTypeInfo) / sizeof(mavTypeInfo[0]); -#endif - AirframeComponent::AirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent(vehicle, autopilot, parent), _name(tr("Airframe")) { -#if 0 - // Broken by latest mavlink module changes. Not used yet. Comment out for now. - // Discussing mavlink fix. - Q_UNUSED(mavTypeInfo); // Keeping this around for later use - - // Validate that our mavTypeInfo array hasn't gotten out of sync - - qDebug() << cMavTypes << MAV_TYPE_ENUM_END; - Q_ASSERT(cMavTypes == MAV_TYPE_ENUM_END); - - static const int mavTypes[] = { - MAV_TYPE_GENERIC, - MAV_TYPE_FIXED_WING, - MAV_TYPE_QUADROTOR, - MAV_TYPE_COAXIAL, - MAV_TYPE_HELICOPTER, - MAV_TYPE_ANTENNA_TRACKER, - MAV_TYPE_GCS, - MAV_TYPE_AIRSHIP, - MAV_TYPE_FREE_BALLOON, - MAV_TYPE_ROCKET, - MAV_TYPE_GROUND_ROVER, - MAV_TYPE_SURFACE_BOAT, - MAV_TYPE_SUBMARINE, - MAV_TYPE_HEXAROTOR, - MAV_TYPE_OCTOROTOR, - MAV_TYPE_TRICOPTER, - MAV_TYPE_FLAPPING_WING, - MAV_TYPE_KITE, - MAV_TYPE_ONBOARD_CONTROLLER, - MAV_TYPE_VTOL_DUOROTOR, - MAV_TYPE_VTOL_QUADROTOR, - MAV_TYPE_VTOL_RESERVED1, - MAV_TYPE_VTOL_RESERVED2, - MAV_TYPE_VTOL_RESERVED3, - MAV_TYPE_VTOL_RESERVED4, - MAV_TYPE_VTOL_RESERVED5, - MAV_TYPE_GIMBAL, - }; - Q_UNUSED(mavTypes); // Keeping this around for later use - - for (size_t i=0; iautostartId) { - Q_ASSERT(!autostartFound); + if (autostartFound) { + qWarning() << "AirframeComponentController::AirframeComponentController duplicate ids found:" << _autostartId; + } autostartFound = true; _currentAirframeType = pType->name; _currentVehicleName = pInfo->name; diff --git a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc index e542694b29f456caa7b0bb4802e3a38f8964d7ce..c7296609927e41f126cc06b9ed51fc1347b9b4f2 100644 --- a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc +++ b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc @@ -30,7 +30,6 @@ PX4AirframeLoader::PX4AirframeLoader(AutoPilotPlugin* autopilot, UASInterface* u Q_UNUSED(autopilot); Q_UNUSED(uas); Q_UNUSED(parent); - Q_ASSERT(uas); } QString PX4AirframeLoader::aiframeMetaDataFile(void) @@ -51,7 +50,10 @@ void PX4AirframeLoader::loadAirframeMetaData(void) qCDebug(PX4AirframeLoaderLog) << "Loading PX4 airframe fact meta data"; - Q_ASSERT(AirframeComponentAirframes::get().count() == 0); + if (AirframeComponentAirframes::get().count() != 0) { + qCWarning(PX4AirframeLoaderLog) << "Internal error"; + return; + } QString airframeFilename; @@ -67,11 +69,12 @@ void PX4AirframeLoader::loadAirframeMetaData(void) qCDebug(PX4AirframeLoaderLog) << "Loading meta data file:" << airframeFilename; QFile xmlFile(airframeFilename); - Q_ASSERT(xmlFile.exists()); + if (!xmlFile.exists()) { + qCWarning(PX4AirframeLoaderLog) << "Internal error"; + return; + } bool success = xmlFile.open(QIODevice::ReadOnly); - Q_UNUSED(success); - Q_ASSERT(success); if (!success) { qCWarning(PX4AirframeLoaderLog) << "Failed opening airframe XML"; diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index 383e5f703b558512e8a6ebe761be893c27306446..7fef798bcd6d494faacaaa259461b7676f3ba40e 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -41,7 +41,10 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) , _tuningComponent(NULL) , _mixersComponent(NULL) { - Q_ASSERT(vehicle); + if (!vehicle) { + qWarning() << "Internal error"; + return; + } _airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this); Q_CHECK_PTR(_airframeFacts); @@ -57,68 +60,70 @@ PX4AutoPilotPlugin::~PX4AutoPilotPlugin() const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) { if (_components.count() == 0 && !_incorrectParameterVersion) { - Q_ASSERT(_vehicle); - - if (_vehicle->parameterManager()->parametersReady()) { - _airframeComponent = new AirframeComponent(_vehicle, this); - _airframeComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); - - _radioComponent = new PX4RadioComponent(_vehicle, this); - _radioComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_radioComponent)); - - if (!_vehicle->hilMode()) { - _sensorsComponent = new SensorsComponent(_vehicle, this); - _sensorsComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent)); - } - - _flightModesComponent = new FlightModesComponent(_vehicle, this); - _flightModesComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent)); - - _powerComponent = new PowerComponent(_vehicle, this); - _powerComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_powerComponent)); + if (_vehicle) { + if (_vehicle->parameterManager()->parametersReady()) { + _airframeComponent = new AirframeComponent(_vehicle, this); + _airframeComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); + + _radioComponent = new PX4RadioComponent(_vehicle, this); + _radioComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_radioComponent)); + + if (!_vehicle->hilMode()) { + _sensorsComponent = new SensorsComponent(_vehicle, this); + _sensorsComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent)); + } + + _flightModesComponent = new FlightModesComponent(_vehicle, this); + _flightModesComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent)); + + _powerComponent = new PowerComponent(_vehicle, this); + _powerComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_powerComponent)); #if 0 - // Coming soon - _motorComponent = new MotorComponent(_vehicle, this); - _motorComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_motorComponent)); + // Coming soon + _motorComponent = new MotorComponent(_vehicle, this); + _motorComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_motorComponent)); #endif - _safetyComponent = new SafetyComponent(_vehicle, this); - _safetyComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); + _safetyComponent = new SafetyComponent(_vehicle, this); + _safetyComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); - _tuningComponent = new PX4TuningComponent(_vehicle, this); - _tuningComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_tuningComponent)); + _tuningComponent = new PX4TuningComponent(_vehicle, this); + _tuningComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_tuningComponent)); #if 0 - // Coming soon - _mixersComponent = new MixersComponent(_vehicle, this); - _mixersComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_mixersComponent)); + // Coming soon + _mixersComponent = new MixersComponent(_vehicle, this); + _mixersComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_mixersComponent)); #endif - //-- Is there support for cameras? - if(_vehicle->parameterManager()->parameterExists(_vehicle->id(), "TRIG_MODE")) { - _cameraComponent = new CameraComponent(_vehicle, this); - _cameraComponent->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent)); - } - - //-- Is there an ESP8266 Connected? - if(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) { - _esp8266Component = new ESP8266Component(_vehicle, this); - _esp8266Component->setupTriggerSignals(); - _components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component)); + //-- Is there support for cameras? + if(_vehicle->parameterManager()->parameterExists(_vehicle->id(), "TRIG_MODE")) { + _cameraComponent = new CameraComponent(_vehicle, this); + _cameraComponent->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent)); + } + + //-- Is there an ESP8266 Connected? + if(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) { + _esp8266Component = new ESP8266Component(_vehicle, this); + _esp8266Component->setupTriggerSignals(); + _components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component)); + } + } else { + qWarning() << "Call to vehicleCompenents prior to parametersReady"; } } else { - qWarning() << "Call to vehicleCompenents prior to parametersReady"; + qWarning() << "Internal error"; } } diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.qml b/src/AutoPilotPlugins/PX4/SafetyComponent.qml index 80b5307914810ea0918fe50175967fc7f1422f6b..5e7b99a9060f261c73d631433329bc42a5588f2e 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.qml @@ -123,7 +123,7 @@ SetupPage { sourceSize.height: height mipmap: true fillMode: Image.PreserveAspectFit - source: "/qmlimages/check.png"///qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/LowBatteryLight.svg" : "/qmlimages/LowBattery.svg" + source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/LowBatteryLight.svg" : "/qmlimages/LowBattery.svg" Layout.rowSpan: 3 Layout.minimumWidth: _imageWidth } @@ -177,7 +177,7 @@ SetupPage { sourceSize.height: height mipmap: true fillMode: Image.PreserveAspectFit - //source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/RCLossLight.svg" : "/qmlimages/RCLoss.svg" + source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/RCLossLight.svg" : "/qmlimages/RCLoss.svg" Layout.rowSpan: 3 Layout.minimumWidth: _imageWidth } @@ -222,7 +222,7 @@ SetupPage { sourceSize.height: height mipmap: true fillMode: Image.PreserveAspectFit - //source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/DatalinkLossLight.svg" : "/qmlimages/DatalinkLoss.svg" + source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/DatalinkLossLight.svg" : "/qmlimages/DatalinkLoss.svg" Layout.rowSpan: 3 Layout.minimumWidth: _imageWidth } @@ -267,7 +267,7 @@ SetupPage { sourceSize.height: height mipmap: true fillMode: Image.PreserveAspectFit - //source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/GeoFenceLight.svg" : "/qmlimages/GeoFence.svg" + source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/GeoFenceLight.svg" : "/qmlimages/GeoFence.svg" Layout.rowSpan: 3 Layout.minimumWidth: _imageWidth } @@ -330,7 +330,7 @@ SetupPage { sourceSize.height: height mipmap: true fillMode: Image.PreserveAspectFit - //source: controller.vehicle.fixedWing ? "/qmlimages/ReturnToHomeAltitude.svg" : "/qmlimages/ReturnToHomeAltitudeCopter.svg" + source: controller.vehicle.fixedWing ? "/qmlimages/ReturnToHomeAltitude.svg" : "/qmlimages/ReturnToHomeAltitudeCopter.svg" Layout.rowSpan: 7 Layout.minimumWidth: _imageWidth } @@ -424,7 +424,7 @@ SetupPage { sourceSize.height: height mipmap: true fillMode: Image.PreserveAspectFit - //source: controller.vehicle.fixedWing ? "/qmlimages/LandMode.svg" : "/qmlimages/LandModeCopter.svg" + source: controller.vehicle.fixedWing ? "/qmlimages/LandMode.svg" : "/qmlimages/LandModeCopter.svg" Layout.rowSpan: landVelocityLabel.visible ? 2 : 1 Layout.minimumWidth: _imageWidth } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 7150e49c4bd2c7bdafa77d988eeb6125092a2c42..b0016e76d29a68a1fb8e46d254676b88685b9d12 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -73,7 +73,10 @@ bool SensorsComponentController::usingUDPLink(void) /// Appends the specified text to the status log area in the ui void SensorsComponentController::_appendStatusLog(const QString& text) { - Q_ASSERT(_statusLog); + if (!_statusLog) { + qWarning() << "Internal error"; + return; + } QVariant returnedValue; QVariant varText = text; @@ -229,8 +232,11 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in bool ok; int p = percent.toInt(&ok); if (ok) { - Q_ASSERT(_progressBar); - _progressBar->setProperty("value", (float)(p / 100.0)); + if (_progressBar) { + _progressBar->setProperty("value", (float)(p / 100.0)); + } else { + qWarning() << "Internal error"; + } } return; } @@ -324,7 +330,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in _gyroCalInProgress = true; _orientationCalDownSideVisible = true; } else { - Q_ASSERT(false); + qWarning() << "Unknown calibration message type" << text; } emit orientationCalSidesDoneChanged(); emit orientationCalSidesVisibleChanged(); diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 2546f6b2de106f0b9a220736fe33cc82a7618a7c..07fb0c0bfd2fe7d166fad36ab71dfc35e97ae02b 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -303,11 +303,15 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString _dataMutex.unlock(); - Q_ASSERT(_mapParameterName2Variant[componentId].contains(parameterName)); - - Fact* fact = _mapParameterName2Variant[componentId][parameterName].value(); - Q_ASSERT(fact); - fact->_containerSetRawValue(value); + Fact* fact = NULL; + if (_mapParameterName2Variant[componentId].contains(parameterName)) { + fact = _mapParameterName2Variant[componentId][parameterName].value(); + } + if (fact) { + fact->_containerSetRawValue(value); + } else { + qWarning() << "Internal error"; + } if (componentParamsComplete) { if (componentId == _vehicle->defaultComponentId()) { @@ -352,18 +356,24 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString void ParameterManager::_valueUpdated(const QVariant& value) { Fact* fact = qobject_cast(sender()); - Q_ASSERT(fact); + if (!fact) { + qWarning() << "Internal error"; + return; + } int componentId = fact->componentId(); QString name = fact->name(); _dataMutex.lock(); - Q_ASSERT(_waitingWriteParamNameMap.contains(componentId)); - _waitingWriteParamNameMap[componentId].remove(name); // Remove any old entry - _waitingWriteParamNameMap[componentId][name] = 0; // Add new entry and set retry count - _waitingParamTimeoutTimer.start(); - _saveRequired = true; + if (_waitingWriteParamNameMap.contains(componentId)) { + _waitingWriteParamNameMap[componentId].remove(name); // Remove any old entry + _waitingWriteParamNameMap[componentId][name] = 0; // Add new entry and set retry count + _waitingParamTimeoutTimer.start(); + _saveRequired = true; + } else { + qWarning() << "Internal error"; + } _dataMutex.unlock(); @@ -397,7 +407,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) _dataMutex.unlock(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); - Q_ASSERT(mavlink); mavlink_message_t msg; mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(), @@ -432,8 +441,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& name) _dataMutex.lock(); - Q_ASSERT(_waitingReadParamNameMap.contains(componentId)); - if (_waitingReadParamNameMap.contains(componentId)) { QString mappedParamName = _remapParamNameToVersion(name); @@ -441,6 +448,8 @@ void ParameterManager::refreshParameter(int componentId, const QString& name) _waitingReadParamNameMap[componentId][mappedParamName] = 0; // Add new wait entry and update retry count qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout"; _waitingParamTimeoutTimer.start(); + } else { + qWarning() << "Internal error"; } _dataMutex.unlock(); diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index a3c9e1e20a094da692504cdb6a17e980e817bc22..e89fe305975540738876ef85f60a0939e482c93c 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -79,7 +79,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData return; } _parameterMetaDataLoaded = true; - + qCDebug(PX4ParameterMetaDataLog) << "Loading parameter meta data:" << metaDataFile; QFile xmlFile(metaDataFile); @@ -218,136 +218,132 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData } if (!badMetaData) { - if (elementName == "short_desc") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - text = text.replace("\n", " "); - qCDebug(PX4ParameterMetaDataLog) << "Short description:" << text; - metaData->setShortDescription(text); - - } else if (elementName == "long_desc") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - text = text.replace("\n", " "); - qCDebug(PX4ParameterMetaDataLog) << "Long description:" << text; - metaData->setLongDescription(text); - - } else if (elementName == "min") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterMetaDataLog) << "Min:" << text; - - QVariant varMin; - if (metaData->convertAndValidateRaw(text, true /* convertOnly */, varMin, errorString)) { - metaData->setRawMin(varMin); - } else { - qCWarning(PX4ParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; - } - - } else if (elementName == "max") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterMetaDataLog) << "Max:" << text; - - QVariant varMax; - if (metaData->convertAndValidateRaw(text, true /* convertOnly */, varMax, errorString)) { - metaData->setRawMax(varMax); - } else { - qCWarning(PX4ParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; - } - - } else if (elementName == "unit") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterMetaDataLog) << "Unit:" << text; - metaData->setRawUnits(text); - - } else if (elementName == "decimal") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterMetaDataLog) << "Decimal:" << text; - - bool convertOk; - QVariant varDecimals = QVariant(text).toUInt(&convertOk); - if (convertOk) { - metaData->setDecimalPlaces(varDecimals.toInt()); - } else { - qCWarning(PX4ParameterMetaDataLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number"; - } + if (metaData) { + if (elementName == "short_desc") { + QString text = xml.readElementText(); + text = text.replace("\n", " "); + qCDebug(PX4ParameterMetaDataLog) << "Short description:" << text; + metaData->setShortDescription(text); + + } else if (elementName == "long_desc") { + QString text = xml.readElementText(); + text = text.replace("\n", " "); + qCDebug(PX4ParameterMetaDataLog) << "Long description:" << text; + metaData->setLongDescription(text); + + } else if (elementName == "min") { + QString text = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "Min:" << text; + + QVariant varMin; + if (metaData->convertAndValidateRaw(text, true /* convertOnly */, varMin, errorString)) { + metaData->setRawMin(varMin); + } else { + qCWarning(PX4ParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; + } - } else if (elementName == "reboot_required") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterMetaDataLog) << "RebootRequired:" << text; - if (text.compare("true", Qt::CaseInsensitive) == 0) { - metaData->setRebootRequired(true); - } + } else if (elementName == "max") { + QString text = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "Max:" << text; - } else if (elementName == "values") { - // doing nothing individual value will follow anyway. May be used for sanity checking. + QVariant varMax; + if (metaData->convertAndValidateRaw(text, true /* convertOnly */, varMax, errorString)) { + metaData->setRawMax(varMax); + } else { + qCWarning(PX4ParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; + } - } else if (elementName == "value") { - QString enumValueStr = xml.attributes().value("code").toString(); - QString enumString = xml.readElementText(); - qCDebug(PX4ParameterMetaDataLog) << "parameter value:" - << "value desc:" << enumString << "code:" << enumValueStr; + } else if (elementName == "unit") { + QString text = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "Unit:" << text; + metaData->setRawUnits(text); - QVariant enumValue; - QString errorString; - if (metaData->convertAndValidateRaw(enumValueStr, false /* validate */, enumValue, errorString)) { - metaData->addEnumInfo(enumString, enumValue); - } else { - qCDebug(PX4ParameterMetaDataLog) << "Invalid enum value, name:" << metaData->name() - << " type:" << metaData->type() << " value:" << enumValueStr - << " error:" << errorString; - } - } else if (elementName == "increment") { - Q_ASSERT(metaData); - double increment; - bool ok; - QString text = xml.readElementText(); - increment = text.toDouble(&ok); - if (ok) { - metaData->setIncrement(increment); - } else { - qCWarning(PX4ParameterMetaDataLog) << "Invalid value for increment, name:" << metaData->name() << " increment:" << text; - } + } else if (elementName == "decimal") { + QString text = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "Decimal:" << text; + + bool convertOk; + QVariant varDecimals = QVariant(text).toUInt(&convertOk); + if (convertOk) { + metaData->setDecimalPlaces(varDecimals.toInt()); + } else { + qCWarning(PX4ParameterMetaDataLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number"; + } - } else if (elementName == "boolean") { - QVariant enumValue; - metaData->convertAndValidateRaw(1, false /* validate */, enumValue, errorString); - metaData->addEnumInfo(tr("Enabled"), enumValue); - metaData->convertAndValidateRaw(0, false /* validate */, enumValue, errorString); - metaData->addEnumInfo(tr("Disabled"), enumValue); - - } else if (elementName == "bitmask") { - // doing nothing individual bits will follow anyway. May be used for sanity checking. - - } else if (elementName == "bit") { - bool ok = false; - unsigned char bit = xml.attributes().value("index").toString().toUInt(&ok); - if (ok) { - QString bitDescription = xml.readElementText(); + } else if (elementName == "reboot_required") { + QString text = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "RebootRequired:" << text; + if (text.compare("true", Qt::CaseInsensitive) == 0) { + metaData->setRebootRequired(true); + } + + } else if (elementName == "values") { + // doing nothing individual value will follow anyway. May be used for sanity checking. + + } else if (elementName == "value") { + QString enumValueStr = xml.attributes().value("code").toString(); + QString enumString = xml.readElementText(); qCDebug(PX4ParameterMetaDataLog) << "parameter value:" - << "index:" << bit << "description:" << bitDescription; - - if (bit < 31) { - QVariant bitmaskRawValue = 1 << bit; - QVariant bitmaskValue; - QString errorString; - if (metaData->convertAndValidateRaw(bitmaskRawValue, true, bitmaskValue, errorString)) { - metaData->addBitmaskInfo(bitDescription, bitmaskValue); + << "value desc:" << enumString << "code:" << enumValueStr; + + QVariant enumValue; + QString errorString; + if (metaData->convertAndValidateRaw(enumValueStr, false /* validate */, enumValue, errorString)) { + metaData->addEnumInfo(enumString, enumValue); + } else { + qCDebug(PX4ParameterMetaDataLog) << "Invalid enum value, name:" << metaData->name() + << " type:" << metaData->type() << " value:" << enumValueStr + << " error:" << errorString; + } + } else if (elementName == "increment") { + double increment; + bool ok; + QString text = xml.readElementText(); + increment = text.toDouble(&ok); + if (ok) { + metaData->setIncrement(increment); + } else { + qCWarning(PX4ParameterMetaDataLog) << "Invalid value for increment, name:" << metaData->name() << " increment:" << text; + } + + } else if (elementName == "boolean") { + QVariant enumValue; + metaData->convertAndValidateRaw(1, false /* validate */, enumValue, errorString); + metaData->addEnumInfo(tr("Enabled"), enumValue); + metaData->convertAndValidateRaw(0, false /* validate */, enumValue, errorString); + metaData->addEnumInfo(tr("Disabled"), enumValue); + + } else if (elementName == "bitmask") { + // doing nothing individual bits will follow anyway. May be used for sanity checking. + + } else if (elementName == "bit") { + bool ok = false; + unsigned char bit = xml.attributes().value("index").toString().toUInt(&ok); + if (ok) { + QString bitDescription = xml.readElementText(); + qCDebug(PX4ParameterMetaDataLog) << "parameter value:" + << "index:" << bit << "description:" << bitDescription; + + if (bit < 31) { + QVariant bitmaskRawValue = 1 << bit; + QVariant bitmaskValue; + QString errorString; + if (metaData->convertAndValidateRaw(bitmaskRawValue, true, bitmaskValue, errorString)) { + metaData->addBitmaskInfo(bitDescription, bitmaskValue); + } else { + qCDebug(PX4ParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name() + << " type:" << metaData->type() << " value:" << bitmaskValue + << " error:" << errorString; + } } else { - qCDebug(PX4ParameterMetaDataLog) << "Invalid bitmask value, name:" << metaData->name() - << " type:" << metaData->type() << " value:" << bitmaskValue - << " error:" << errorString; + qCWarning(PX4ParameterMetaDataLog) << "Invalid value for bitmask, bit:" << bit; } - } else { - qCWarning(PX4ParameterMetaDataLog) << "Invalid value for bitmask, bit:" << bit; } + } else { + qCDebug(PX4ParameterMetaDataLog) << "Unknown element in XML: " << elementName; } } else { - qCDebug(PX4ParameterMetaDataLog) << "Unknown element in XML: " << elementName; + qWarning() << "Internal error"; } } } @@ -358,12 +354,12 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData // Done loading this parameter, validate default value if (metaData->defaultValueAvailable()) { QVariant var; - + if (!metaData->convertAndValidateRaw(metaData->rawDefaultValue(), false /* convertOnly */, var, errorString)) { qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->rawDefaultValue() << " error:" << errorString; } } - + // Reset for next parameter metaData = NULL; badMetaData = false; diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index cff60f287f3fba817d190d9fdd1368ac1f398f21..3e38ee151f56202779f93afea5c40ea0819ec0dd 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -245,9 +245,9 @@ FlightMap { } } - // Camera points + // Camera trigger points MapItemView { - model: _missionController.cameraPoints + model: _activeVehicle ? _activeVehicle.cameraTriggerPoints : 0 delegate: CameraTriggerIndicator { coordinate: object.coordinate diff --git a/src/GPS/GPSManager.cc b/src/GPS/GPSManager.cc index 0c7c8406bdbfa5b76e03a15dd54637a99bd83524..0d1a28fb2e3ba00d53d65a6661af29c35bf31b5f 100644 --- a/src/GPS/GPSManager.cc +++ b/src/GPS/GPSManager.cc @@ -28,8 +28,6 @@ GPSManager::~GPSManager() void GPSManager::connectGPS(const QString& device) { - Q_ASSERT(_toolbox); - RTKSettings* rtkSettings = qgcApp()->toolbox()->settingsManager()->rtkSettings(); cleanup(); diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 158c7b902a3c3d892c87275b5d2f69590e7bbf7d..61ae05f372a85504545fac64c62a3391c336c98c 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1384,7 +1384,6 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle) connect(_missionManager, &MissionManager::currentIndexChanged, this, &MissionController::_currentMissionIndexChanged); connect(_missionManager, &MissionManager::lastCurrentIndexChanged, this, &MissionController::resumeMissionIndexChanged); connect(_missionManager, &MissionManager::resumeMissionReady, this, &MissionController::resumeMissionReady); - connect(_missionManager, &MissionManager::cameraFeedback, this, &MissionController::_cameraFeedback); connect(_managerVehicle, &Vehicle::homePositionChanged, this, &MissionController::_managerVehicleHomePositionChanged); connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatus); connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatus); @@ -1664,19 +1663,6 @@ void MissionController::applyDefaultMissionAltitude(void) } } -void MissionController::_cameraFeedback(QGeoCoordinate imageCoordinate, int index) -{ - Q_UNUSED(index); - if (!_editMode) { - _cameraPoints.append(new QGCQGeoCoordinate(imageCoordinate, this)); - } -} - -void MissionController::clearCameraPoints(void) -{ - _cameraPoints.clearAndDeleteContents(); -} - void MissionController::_progressPctChanged(double progressPct) { if (!qFuzzyCompare(progressPct, _progressPct)) { diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index b784ace6113b500946b3d10139f93a4879e31dd8..9e22b38bdd6e416939922e23e1ca03ce713cfd2e 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -64,7 +64,6 @@ public: Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged) Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) - Q_PROPERTY(QmlObjectListModel* cameraPoints READ cameraPoints CONSTANT) Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) @@ -106,8 +105,6 @@ public: /// Sends the mission items to the specified vehicle static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems); - Q_INVOKABLE void clearCameraPoints(void); - bool loadJsonFile(QFile& file, QString& errorString); bool loadTextFile(QFile& file, QString& errorString); @@ -130,7 +127,6 @@ public: QmlObjectListModel* visualItems (void) { return _visualItems; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; } - QmlObjectListModel* cameraPoints (void) { return &_cameraPoints; } QStringList complexMissionItemNames (void) const; QGeoCoordinate plannedHomePosition (void) const; double progressPct (void) const { return _progressPct; } @@ -178,7 +174,6 @@ private slots: void _recalcWaypointLines(void); void _recalcMissionFlightStatus(void); void _updateContainsItems(void); - void _cameraFeedback(QGeoCoordinate imageCoordinate, int index); void _progressPctChanged(double progressPct); void _visualItemsDirtyChanged(bool dirty); void _managerSendComplete(void); @@ -220,7 +215,6 @@ private: QmlObjectListModel* _visualItems; MissionSettingsItem* _settingsItem; QmlObjectListModel _waypointLines; - QmlObjectListModel _cameraPoints; CoordVectHashTable _linesTable; bool _firstItemsFromVehicle; bool _itemsRequested; diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index feb3d93fc506354119dd66bc1135e67b432a4f48..c45b29cb4b0dc09f8549ee3950fd89e1c2793b31 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -680,31 +680,6 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message) break; } } - -void MissionManager::_handleCameraFeedback(const mavlink_message_t& message) -{ - mavlink_camera_feedback_t feedback; - - mavlink_msg_camera_feedback_decode(&message, &feedback); - - QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl); - qCDebug(MissionManagerLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx; - emit cameraFeedback(imageCoordinate, feedback.img_idx); -} - -void MissionManager::_handleCameraImageCaptured(const mavlink_message_t& message) -{ - mavlink_camera_image_captured_t feedback; - - mavlink_msg_camera_image_captured_decode(&message, &feedback); - - QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt); - qCDebug(MissionManagerLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result; - if (feedback.capture_result == 1) { - emit cameraFeedback(imageCoordinate, feedback.image_index); - } -} - /// Called when a new mavlink message for out vehicle is received void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message) { @@ -740,14 +715,6 @@ void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message) case MAVLINK_MSG_ID_MISSION_CURRENT: _handleMissionCurrent(message); break; - - case MAVLINK_MSG_ID_CAMERA_FEEDBACK: - _handleCameraFeedback(message); - break; - - case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED: - _handleCameraImageCaptured(message); - break; } } diff --git a/src/MissionManager/MissionManager.h b/src/MissionManager/MissionManager.h index 8b47d6439e27d6cfa10ec24526ccd93804e24c28..6dbc5230385bede1ff9ba70d178256b05876e99a 100644 --- a/src/MissionManager/MissionManager.h +++ b/src/MissionManager/MissionManager.h @@ -88,7 +88,6 @@ signals: void currentIndexChanged(int currentIndex); void lastCurrentIndexChanged(int lastCurrentIndex); void resumeMissionReady(void); - void cameraFeedback(QGeoCoordinate imageCoordinate, int index); void progressPct(double progressPercentPct); void removeAllComplete (void); void sendComplete (void); @@ -122,8 +121,6 @@ private: void _handleMissionRequest(const mavlink_message_t& message, bool missionItemInt); void _handleMissionAck(const mavlink_message_t& message); void _handleMissionCurrent(const mavlink_message_t& message); - void _handleCameraFeedback(const mavlink_message_t& message); - void _handleCameraImageCaptured(const mavlink_message_t& message); void _requestNextMissionItem(void); void _clearMissionItems(void); void _sendError(ErrorCode_t errorCode, const QString& errorMsg); diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 779bbdde6d30531425e6178edac5194ecbcaac55..e68c3e74274cd3582d37db9303df5f4042daed33 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -231,7 +231,8 @@ QGCView { id: fileDialog qgcView: _qgcView folder: QGroundControl.settingsManager.appSettings.missionSavePath - fileExtension: masterController.fileExtension + fileExtension: QGroundControl.settingsManager.appSettings.planFileExtension + fileExtension2: QGroundControl.settingsManager.appSettings.missionFileExtension onAcceptedForSave: { masterController.saveToFile(file) @@ -653,7 +654,7 @@ QGCView { id: syncLoadFromFileOverwrite QGCViewMessage { id: syncLoadFromVehicleCheck - message: qsTr("You have unsaved/unsent changes. Loading a from a file will lose these changes. Are you sure you want to load from a file?") + message: qsTr("You have unsaved/unsent changes. Loading from a file will lose these changes. Are you sure you want to load from a file?") function accept() { hideDialog() masterController.loadFromSelectedFile() diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index f132c181fc50be1d3458ccb1e178f42a0fb853bd..7bbdfd009cbb188f570cccc9441e7f075d2ea16e 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -176,7 +176,6 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) , _toolbox(NULL) , _bluetoothAvailable(false) { - Q_ASSERT(_app == NULL); _app = this; // This prevents usage of QQuickWidget to fail since it doesn't support native widget siblings @@ -193,11 +192,11 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) if (getuid() == 0) { QMessageBox msgBox; msgBox.setInformativeText(tr("You are running %1 as root. " - "You should not do this since it will cause other issues with %1. " - "%1 will now exit. " - "If you are having serial port issues on Ubuntu, execute the following commands to fix most issues:\n" - "sudo usermod -a -G dialout $USER\n" - "sudo apt-get remove modemmanager").arg(qgcApp()->applicationName())); + "You should not do this since it will cause other issues with %1. " + "%1 will now exit. " + "If you are having serial port issues on Ubuntu, execute the following commands to fix most issues:\n" + "sudo usermod -a -G dialout $USER\n" + "sudo apt-get remove modemmanager").arg(qgcApp()->applicationName())); msgBox.setStandardButtons(QMessageBox::Ok); msgBox.setDefaultButton(QMessageBox::Ok); msgBox.exec(); @@ -473,7 +472,6 @@ void QGCApplication::clearDeleteAllSettingsNextBoot(void) /// @brief Returns the QGCApplication object singleton. QGCApplication* qgcApp(void) { - Q_ASSERT(QGCApplication::_app); return QGCApplication::_app; } @@ -612,19 +610,19 @@ void QGCApplication::reportMissingParameter(int componentId, const QString& name /// Called when the delay timer fires to show the missing parameters warning void QGCApplication::_missingParamsDisplay(void) { - Q_ASSERT(_missingParams.count()); - - QString params; - foreach (const QString &name, _missingParams) { - if (params.isEmpty()) { - params += name; - } else { - params += QString(", %1").arg(name); + if (_missingParams.count()) { + QString params; + foreach (const QString &name, _missingParams) { + if (params.isEmpty()) { + params += name; + } else { + params += QString(", %1").arg(name); + } } - } - _missingParams.clear(); + _missingParams.clear(); - showMessage(QString("Parameters are missing from firmware. You may be running a version of firmware QGC does not work correctly with or your firmware has a bug in it. Missing params: %1").arg(params)); + showMessage(QString("Parameters are missing from firmware. You may be running a version of firmware QGC does not work correctly with or your firmware has a bug in it. Missing params: %1").arg(params)); + } } QObject* QGCApplication::_rootQmlObject() diff --git a/src/QGCFileDownload.cc b/src/QGCFileDownload.cc index be15da1ea07d01b5892c79936a50d2414a8368eb..9c3cdd0274ed073e7dd4df5b23403d656d25572c 100644 --- a/src/QGCFileDownload.cc +++ b/src/QGCFileDownload.cc @@ -110,19 +110,24 @@ void QGCFileDownload::_downloadFinished(void) // Download file location is in user attribute QString downloadFilename = reply->request().attribute(QNetworkRequest::User).toString(); - Q_ASSERT(!downloadFilename.isEmpty()); - - // Store downloaded file in download location - QFile file(downloadFilename); - if (!file.open(QIODevice::WriteOnly)) { - emit error(QString("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString())); - return; - } - - file.write(reply->readAll()); - file.close(); - emit downloadFinished(_originalRemoteFile, downloadFilename); + if (!downloadFilename.isEmpty()) { + // Store downloaded file in download location + QFile file(downloadFilename); + if (!file.open(QIODevice::WriteOnly)) { + emit error(QString("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString())); + return; + } + + file.write(reply->readAll()); + file.close(); + + emit downloadFinished(_originalRemoteFile, downloadFilename); + } else { + QString errorMsg = "Internal error"; + qWarning() << errorMsg; + emit error(errorMsg); + } } /// @brief Called when an error occurs during download diff --git a/src/QGCPalette.cc b/src/QGCPalette.cc index 7eb390cc8b8db83ec5e121d413ba1f7c60f0affe..dd55443472eb98cbd33563b329ecc62f80b78aec 100644 --- a/src/QGCPalette.cc +++ b/src/QGCPalette.cc @@ -39,8 +39,9 @@ QGCPalette::QGCPalette(QObject* parent) : QGCPalette::~QGCPalette() { bool fSuccess = _paletteObjects.removeOne(this); - Q_ASSERT(fSuccess); - Q_UNUSED(fSuccess); + if (!fSuccess) { + qWarning() << "Internal error"; + } } void QGCPalette::_buildMap(void) diff --git a/src/QGCQFileDialog.cc b/src/QGCQFileDialog.cc index 0a4932fcb09020e1f6df42a6ea4b621d31365d95..21fa68b034290492e57cf3730a41f41d02e1db3f 100644 --- a/src/QGCQFileDialog.cc +++ b/src/QGCQFileDialog.cc @@ -126,7 +126,9 @@ QString QGCQFileDialog::getSaveFileName( defaultSuffixCopy = _getFirstExtensionInFilter(filter); } //-- If this is set to strict, we have to have a default extension - Q_ASSERT(defaultSuffixCopy.isEmpty() == false); + if (defaultSuffixCopy.isEmpty()) { + qWarning() << "Internal error"; + } //-- Forcefully append our desired extension result += "."; result += defaultSuffixCopy; @@ -197,9 +199,13 @@ void QGCQFileDialog::_validate(Options& options) Q_UNUSED(options) // You can't use QGCQFileDialog if QGCApplication is not created yet. - Q_ASSERT(qgcApp()); + if (!qgcApp()) { + qWarning() << "Internal error"; + return; + } - Q_ASSERT_X(QThread::currentThread() == qgcApp()->thread(), "Threading issue", "QGCQFileDialog can only be called from main thread"); - if (MainWindow::instance()) { + if (QThread::currentThread() != qgcApp()->thread()) { + qWarning() << "Threading issue: QGCQFileDialog can only be called from main thread"; + return; } } diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 66385dc9edbcdb17681f32c30146559fa7c7d2fe..9520b9eb9783753b6169195b1f52ea104132d274 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -89,8 +89,9 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen void ParameterEditorController::clearRCToParam(void) { - Q_ASSERT(_uas); - _uas->unsetRCToParameterMap(); + if (_uas) { + _uas->unsetRCToParameterMap(); + } } void ParameterEditorController::saveToFile(const QString& filename) @@ -147,9 +148,10 @@ void ParameterEditorController::setRCToParam(const QString& paramName) #ifdef __mobile__ Q_UNUSED(paramName) #else - Q_ASSERT(_uas); - QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(paramName, _uas, qgcApp()->toolbox()->multiVehicleManager(), MainWindow::instance()); - d->exec(); + if (_uas) { + QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(paramName, _uas, qgcApp()->toolbox()->multiVehicleManager(), MainWindow::instance()); + d->exec(); + } #endif } diff --git a/src/QmlControls/QGCCheckBox.qml b/src/QmlControls/QGCCheckBox.qml index 424e244438ea79917e90e2b06d0512608a7b1329..735138d28ec87d8a44f310cc35b72e0217c94054 100644 --- a/src/QmlControls/QGCCheckBox.qml +++ b/src/QmlControls/QGCCheckBox.qml @@ -11,7 +11,7 @@ CheckBox { style: CheckBoxStyle { label: Item { implicitWidth: text.implicitWidth + 2 - implicitHeight: text.implicitHeight + implicitHeight: ScreenTools.implicitCheckBoxHeight baselineOffset: text.baselineOffset Rectangle { @@ -39,7 +39,7 @@ CheckBox { } // label indicator: Item { - implicitWidth: ScreenTools.implicitCheckBoxWidth + implicitWidth: ScreenTools.checkBoxIndicatorSize implicitHeight: implicitWidth Rectangle { diff --git a/src/QmlControls/QGCFileDialog.qml b/src/QmlControls/QGCFileDialog.qml index 64cb4aaa759520f6dd5ca41c3cecc0ea22bca3f0..5ef9432add7e6cf66fd192bb8041dc4ccbbfbe4c 100644 --- a/src/QmlControls/QGCFileDialog.qml +++ b/src/QmlControls/QGCFileDialog.qml @@ -18,6 +18,7 @@ Item { property string folder property var nameFilters property string fileExtension + property string fileExtension2 property string title property bool selectExisting property bool selectFolder @@ -90,7 +91,7 @@ Item { spacing: ScreenTools.defaultFontPixelHeight / 2 Repeater { - id: fileList; + id: fileList model: controller.getFiles(folder, fileExtension) QGCButton { @@ -105,9 +106,25 @@ Item { } } + Repeater { + id: fileList2 + model: fileExtension2 == "" ? [ ] : controller.getFiles(folder, fileExtension2) + + QGCButton { + anchors.left: parent.left + anchors.right: parent.right + text: modelData + + onClicked: { + hideDialog() + _root.acceptedForLoad(controller.fullyQualifiedFilename(folder, modelData, fileExtension2)) + } + } + } + QGCLabel { text: qsTr("No files") - visible: fileList.model.length == 0 + visible: fileList.model.length == 0 && fileList2.model.length == 0 } } } diff --git a/src/QmlControls/QGCRadioButton.qml b/src/QmlControls/QGCRadioButton.qml index 4eba07f153f1cb8bac9e8a0f8261bb8b59577cab..d0ed7c00d072923c35fa09e4f3f1393891ce0ecf 100644 --- a/src/QmlControls/QGCRadioButton.qml +++ b/src/QmlControls/QGCRadioButton.qml @@ -15,7 +15,7 @@ RadioButton { style: RadioButtonStyle { label: Item { implicitWidth: text.implicitWidth + ScreenTools.defaultFontPixelWidth * 0.25 - implicitHeight: text.implicitHeight + implicitHeight: ScreenTools.implicitRadioButtonHeight baselineOffset: text.y + text.baselineOffset Rectangle { @@ -43,5 +43,23 @@ RadioButton { anchors.centerIn: parent } } + + indicator: Rectangle { + width: ScreenTools.radioButtonIndicatorSize + height: width + border.color: qgcPal.text + antialiasing: true + radius: height / 2 + + Rectangle { + anchors.centerIn: parent + width: Math.round(parent.width * 0.5) + height: width + antialiasing: true + radius: height/2 + color: qgcPal.text + opacity: control.checked ? (control.enabled ? 1 : 0.5) : 0 + } + } } } diff --git a/src/QmlControls/ScreenTools.qml b/src/QmlControls/ScreenTools.qml index 324b8fb8b75a6719d5d9fd4fe16be557e8fa1da7..fc13c3d41333867f90cf7e867c581e71a1d14cf5 100644 --- a/src/QmlControls/ScreenTools.qml +++ b/src/QmlControls/ScreenTools.qml @@ -64,13 +64,16 @@ Item { property real minTouchPixels: 0 ///< Minimum touch size in pixels // The implicit heights/widths for our custom control set - property real implicitButtonWidth: Math.round(defaultFontPixelWidth * (isMobile ? 7.0 : 5.0)) - property real implicitButtonHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) - property real implicitCheckBoxWidth: Math.round(defaultFontPixelHeight * (isMobile ? 1.5 : 1.0)) - property real implicitTextFieldHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) - property real implicitComboBoxHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) - property real implicitComboBoxWidth: Math.round(defaultFontPixelWidth * (isMobile ? 7.0 : 5.0)) - property real implicitSliderHeight: isMobile ? Math.max(defaultFontPixelHeight, minTouchPixels) : defaultFontPixelHeight + property real implicitButtonWidth: Math.round(defaultFontPixelWidth * (isMobile ? 7.0 : 5.0)) + property real implicitButtonHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) + property real implicitCheckBoxHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.0)) + property real implicitRadioButtonHeight: implicitCheckBoxHeight + property real implicitTextFieldHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) + property real implicitComboBoxHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) + property real implicitComboBoxWidth: Math.round(defaultFontPixelWidth * (isMobile ? 7.0 : 5.0)) + property real implicitSliderHeight: isMobile ? Math.max(defaultFontPixelHeight, minTouchPixels) : defaultFontPixelHeight + property real checkBoxIndicatorSize: Math.round(defaultFontPixelHeight * (isMobile ? 1.5 : 1.0)) + property real radioButtonIndicatorSize: checkBoxIndicatorSize readonly property string normalFontFamily: "opensans" readonly property string demiboldFontFamily: "opensans-demibold" diff --git a/src/Settings/App.SettingsGroup.json b/src/Settings/App.SettingsGroup.json index 9f66e7c877a606f21ce8989c0ff40d693eb5c941..6686a1b779b44d0a541904e2e5a69dda5b5793c4 100644 --- a/src/Settings/App.SettingsGroup.json +++ b/src/Settings/App.SettingsGroup.json @@ -116,13 +116,6 @@ "type": "bool", "defaultValue": false }, -{ - "name": "AutomaticMissionUpload", - "shortDescription": "Automatic mission upload", - "longDescription": "Automatically upload mission to vehicle after changes", - "type": "bool", - "defaultValue": true -}, { "name": "SavePath", "shortDescription": "Application save directory", diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index bc499e5dc120bd324c8a4df7dfe1c7542efeb682..f5c0051311d363b263760e34207925832c8234ed 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -31,7 +31,6 @@ const char* AppSettings::indoorPaletteName = "StyleIs const char* AppSettings::showLargeCompassName = "ShowLargeCompass"; const char* AppSettings::savePathName = "SavePath"; const char* AppSettings::autoLoadMissionsName = "AutoLoadMissions"; -const char* AppSettings::automaticMissionUploadName = "AutomaticMissionUpload"; const char* AppSettings::parameterFileExtension = "params"; const char* AppSettings::planFileExtension = "plan"; @@ -62,7 +61,6 @@ AppSettings::AppSettings(QObject* parent) , _showLargeCompassFact(NULL) , _savePathFact(NULL) , _autoLoadMissionsFact(NULL) - , _automaticMissionUpload(NULL) { QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); qmlRegisterUncreatableType("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only"); @@ -280,15 +278,6 @@ Fact* AppSettings::autoLoadMissions(void) return _autoLoadMissionsFact; } -Fact* AppSettings::automaticMissionUpload(void) -{ - if (!_automaticMissionUpload) { - _automaticMissionUpload = _createSettingsFact(automaticMissionUploadName); - } - - return _automaticMissionUpload; -} - MAV_AUTOPILOT AppSettings::offlineEditingFirmwareTypeFromFirmwareType(MAV_AUTOPILOT firmwareType) { if (firmwareType != MAV_AUTOPILOT_PX4 && firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) { diff --git a/src/Settings/AppSettings.h b/src/Settings/AppSettings.h index dc2df77490b6fc1c0116ad3af94c18e414aff3cd..fbbfd587456550d5e0e89350744219aa41845f0a 100644 --- a/src/Settings/AppSettings.h +++ b/src/Settings/AppSettings.h @@ -35,7 +35,6 @@ public: Q_PROPERTY(Fact* showLargeCompass READ showLargeCompass CONSTANT) Q_PROPERTY(Fact* savePath READ savePath CONSTANT) Q_PROPERTY(Fact* autoLoadMissions READ autoLoadMissions CONSTANT) - Q_PROPERTY(Fact* automaticMissionUpload READ automaticMissionUpload CONSTANT) Q_PROPERTY(QString missionSavePath READ missionSavePath NOTIFY savePathsChanged) Q_PROPERTY(QString parameterSavePath READ parameterSavePath NOTIFY savePathsChanged) @@ -62,7 +61,6 @@ public: Fact* showLargeCompass (void); Fact* savePath (void); Fact* autoLoadMissions (void); - Fact* automaticMissionUpload (void); QString missionSavePath (void); QString parameterSavePath (void); @@ -88,7 +86,6 @@ public: static const char* showLargeCompassName; static const char* savePathName; static const char* autoLoadMissionsName; - static const char* automaticMissionUploadName; // Application wide file extensions static const char* parameterFileExtension; @@ -127,7 +124,6 @@ private: SettingsFact* _showLargeCompassFact; SettingsFact* _savePathFact; SettingsFact* _autoLoadMissionsFact; - SettingsFact* _automaticMissionUpload; }; #endif diff --git a/src/Vehicle/MAVLinkLogManager.cc b/src/Vehicle/MAVLinkLogManager.cc index ca56c1ff1b50a3ff4a6abdecbdecd520976f30ac..ad5de1d73a1d5156dd654751b6cff56b4124b224 100644 --- a/src/Vehicle/MAVLinkLogManager.cc +++ b/src/Vehicle/MAVLinkLogManager.cc @@ -150,10 +150,10 @@ bool MAVLinkLogProcessor::create(MAVLinkLogManager* manager, const QString path, uint8_t id) { _fileName.sprintf("%s/%03d-%s%s", - path.toLatin1().data(), - id, - QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz").toLatin1().data(), - kUlogExtension); + path.toLatin1().data(), + id, + QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz").toLatin1().data(), + kUlogExtension); _fd = fopen(_fileName.toLatin1().data(), "wb"); if(_fd) { _record = new MAVLinkLogFiles(manager, _fileName, true); @@ -498,17 +498,20 @@ MAVLinkLogManager::uploadLog() } for(int i = 0; i < _logFiles.count(); i++) { _currentLogfile = qobject_cast(_logFiles.get(i)); - Q_ASSERT(_currentLogfile); - if(_currentLogfile->selected()) { - _currentLogfile->setSelected(false); - if(!_currentLogfile->uploaded() && !_emailAddress.isEmpty() && !_uploadURL.isEmpty()) { - _currentLogfile->setUploading(true); - _currentLogfile->setProgress(0.0); - QString filePath = _makeFilename(_currentLogfile->name()); - _sendLog(filePath); - emit uploadingChanged(); - return; + if (_currentLogfile) { + if(_currentLogfile->selected()) { + _currentLogfile->setSelected(false); + if(!_currentLogfile->uploaded() && !_emailAddress.isEmpty() && !_uploadURL.isEmpty()) { + _currentLogfile->setUploading(true); + _currentLogfile->setProgress(0.0); + QString filePath = _makeFilename(_currentLogfile->name()); + _sendLog(filePath); + emit uploadingChanged(); + return; + } } + } else { + qWarning() << "Internal error"; } } _currentLogfile = NULL; @@ -541,9 +544,12 @@ MAVLinkLogManager::_getFirstSelected() { for(int i = 0; i < _logFiles.count(); i++) { MAVLinkLogFiles* f = qobject_cast(_logFiles.get(i)); - Q_ASSERT(f); - if(f->selected()) { - return i; + if (f) { + if(f->selected()) { + return i; + } + } else { + qWarning() << "Internal error"; } } return -1; @@ -590,9 +596,12 @@ MAVLinkLogManager::cancelUpload() { for(int i = 0; i < _logFiles.count(); i++) { MAVLinkLogFiles* pLogFile = qobject_cast(_logFiles.get(i)); - Q_ASSERT(pLogFile); - if(pLogFile->selected() && pLogFile != _currentLogfile) { - pLogFile->setSelected(false); + if (pLogFile) { + if(pLogFile->selected() && pLogFile != _currentLogfile) { + pLogFile->setSelected(false); + } + } else { + qWarning() << "Internal error"; } } if(_currentLogfile) { diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 4e47d692f72de93637af6afd0fa948cdc7775e99..db8b9bec70997dadab8166726d95131a45dd51db 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -29,6 +29,7 @@ #include "MissionCommandTree.h" #include "QGroundControlQmlGlobal.h" #include "SettingsManager.h" +#include "QGCQGeoCoordinate.h" QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") @@ -316,6 +317,10 @@ void Vehicle::_commonInit(void) _missionManager = new MissionManager(this); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete); + connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints); + connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearTrajectoryPoints); + connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints); + connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearTrajectoryPoints); _parameterManager = new ParameterManager(this); connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); @@ -584,6 +589,13 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes break; case MAVLINK_MSG_ID_SCALED_PRESSURE3: _handleScaledPressure3(message); + break; + case MAVLINK_MSG_ID_CAMERA_FEEDBACK: + _handleCameraFeedback(message); + break; + + case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED: + _handleCameraImageCaptured(message); break; case MAVLINK_MSG_ID_SERIAL_CONTROL: @@ -605,6 +617,31 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _uas->receiveMessage(message); } + +void Vehicle::_handleCameraFeedback(const mavlink_message_t& message) +{ + mavlink_camera_feedback_t feedback; + + mavlink_msg_camera_feedback_decode(&message, &feedback); + + QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl); + qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx; + _cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this)); +} + +void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message) +{ + mavlink_camera_image_captured_t feedback; + + mavlink_msg_camera_image_captured_decode(&message, &feedback); + + QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt); + qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result; + if (feedback.capture_result == 1) { + _cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this)); + } +} + void Vehicle::_handleVfrHud(mavlink_message_t& message) { mavlink_vfr_hud_t vfrHud; @@ -945,15 +982,24 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message) // We are transitioning to the armed state, begin tracking trajectory points for the map if (_armed) { _mapTrajectoryStart(); + _clearCameraTriggerPoints(); } else { _mapTrajectoryStop(); } } if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) { + QString previousFlightMode; + if (_base_mode != 0 || _custom_mode != 0){ + // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about + // bad modes while unit testing. + previousFlightMode = flightMode(); + } _base_mode = heartbeat.base_mode; _custom_mode = heartbeat.custom_mode; - emit flightModeChanged(flightMode()); + if (previousFlightMode != flightMode()) { + emit flightModeChanged(flightMode()); + } } } @@ -1277,7 +1323,6 @@ void Vehicle::_handleTextMessage(int newCount) } UASMessageHandler* pMh = qgcApp()->toolbox()->uasMessageHandler(); - Q_ASSERT(pMh); MessageType_t type = newCount ? _currentMessageType : MessageNone; int errorCount = _currentErrorCount; int warnCount = _currentWarningCount; @@ -1622,10 +1667,20 @@ void Vehicle::_addNewMapTrajectoryPoint(void) _mapTrajectoryLastCoordinate = _coordinate; } +void Vehicle::_clearTrajectoryPoints(void) +{ + _mapTrajectoryList.clearAndDeleteContents(); +} + +void Vehicle::_clearCameraTriggerPoints(void) +{ + _cameraTriggerPoints.clearAndDeleteContents(); +} + void Vehicle::_mapTrajectoryStart(void) { _mapTrajectoryHaveFirstCoordinate = false; - _mapTrajectoryList.clear(); + _clearTrajectoryPoints(); _mapTrajectoryTimer.start(); _flightDistanceFact.setRawValue(0); } @@ -1907,11 +1962,6 @@ void Vehicle::_announceArmedChanged(bool armed) _say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? QStringLiteral("armed") : QStringLiteral("disarmed"))); } -void Vehicle::clearTrajectoryPoints(void) -{ - _mapTrajectoryList.clearAndDeleteContents(); -} - void Vehicle::setFlying(bool flying) { if (armed() && _flying != flying) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 8cd5e3c7670c407ecf2dfb14368124026fefd5af..0836fd2ad64eb386a55ade185e13b4dc7e14e15b 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -246,6 +246,7 @@ public: Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged) Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged) Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT) + Q_PROPERTY(QmlObjectListModel* cameraTriggerPoints READ cameraTriggerPoints CONSTANT) Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged) Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged) Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged) @@ -371,8 +372,6 @@ public: Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust); Q_INVOKABLE void disconnectInactiveVehicle(void); - Q_INVOKABLE void clearTrajectoryPoints(void); - /// Command vehicle to return to launch Q_INVOKABLE void guidedModeRTL(void); @@ -524,6 +523,7 @@ public: void setPrearmError(const QString& prearmError); QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; } + QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; } int flowImageIndex() { return _flowImageIndex; } @@ -791,8 +791,9 @@ private slots: void _geoFenceLoadComplete(void); void _rallyPointLoadComplete(void); void _sendMavCommandAgain(void); - void _activeJoystickChanged(void); + void _clearTrajectoryPoints(void); + void _clearCameraTriggerPoints(void); private: bool _containsLink(LinkInterface* link); @@ -820,6 +821,8 @@ private: void _handleScaledPressure(mavlink_message_t& message); void _handleScaledPressure2(mavlink_message_t& message); void _handleScaledPressure3(mavlink_message_t& message); + void _handleCameraFeedback(const mavlink_message_t& message); + void _handleCameraImageCaptured(const mavlink_message_t& message); void _missionManagerError(int errorCode, const QString& errorMsg); void _geoFenceManagerError(int errorCode, const QString& errorMsg); void _rallyPointManagerError(int errorCode, const QString& errorMsg); @@ -954,6 +957,8 @@ private: bool _mapTrajectoryHaveFirstCoordinate; static const int _mapTrajectoryMsecsBetweenPoints = 1000; + QmlObjectListModel _cameraTriggerPoints; + // Toolbox references FirmwarePluginManager* _firmwarePluginManager; JoystickManager* _joystickManager; diff --git a/src/VehicleSetup/VehicleComponent.cc b/src/VehicleSetup/VehicleComponent.cc index 3bfc3c3e5a60c793763282769ac736124c36768b..3afc798ace843aa43f4ed8909e2db2cd4960dd67 100644 --- a/src/VehicleSetup/VehicleComponent.cc +++ b/src/VehicleSetup/VehicleComponent.cc @@ -20,8 +20,9 @@ VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, _vehicle(vehicle), _autopilot(autopilot) { - Q_ASSERT(vehicle); - Q_ASSERT(autopilot); + if (!vehicle || !autopilot) { + qWarning() << "Internal error"; + } } VehicleComponent::~VehicleComponent() @@ -31,19 +32,23 @@ VehicleComponent::~VehicleComponent() void VehicleComponent::addSummaryQmlComponent(QQmlContext* context, QQuickItem* parent) { - Q_ASSERT(context); - - // FIXME: We own this object now, need to delete somewhere - QQmlComponent component(context->engine(), QUrl::fromUserInput("qrc:/qml/VehicleComponentSummaryButton.qml")); - if (component.status() == QQmlComponent::Error) { - qDebug() << component.errors(); - Q_ASSERT(false); + if (context) { + // FIXME: We own this object now, need to delete somewhere + QQmlComponent component(context->engine(), QUrl::fromUserInput("qrc:/qml/VehicleComponentSummaryButton.qml")); + if (component.status() == QQmlComponent::Error) { + qWarning() << component.errors(); + } else { + QQuickItem* item = qobject_cast(component.create(context)); + if (item) { + item->setParentItem(parent); + item->setProperty("vehicleComponent", QVariant::fromValue(this)); + } else { + qWarning() << "Internal error"; + } + } + } else { + qWarning() << "Internal error"; } - - QQuickItem* item = qobject_cast(component.create(context)); - Q_ASSERT(item); - item->setParentItem(parent); - item->setProperty("vehicleComponent", QVariant::fromValue(this)); } void VehicleComponent::setupTriggerSignals(void) diff --git a/src/ViewWidgets/ViewWidgetController.cc b/src/ViewWidgets/ViewWidgetController.cc index c9651908b9a7252d92464e5268980d697a0a64a3..3a3ba13d53742daa7c4de97f132da1c52060ef49 100644 --- a/src/ViewWidgets/ViewWidgetController.cc +++ b/src/ViewWidgets/ViewWidgetController.cc @@ -33,11 +33,11 @@ void ViewWidgetController::_vehicleAvailable(bool available) _uas = vehicle->uas(); _autopilot = vehicle->autopilotPlugin(); - Q_ASSERT(_autopilot); emit pluginConnected(QVariant::fromValue(_autopilot)); } } -Q_INVOKABLE void ViewWidgetController::checkForVehicle(void) + +void ViewWidgetController::checkForVehicle(void) { _vehicleAvailable(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); } diff --git a/src/comm/LinkInterface.cc b/src/comm/LinkInterface.cc index 9361fb2b77faf1421d56d9db874a19e6d4d61aa7..f995fd10482bd51ff7010b06d8eb2697e65a1d51 100644 --- a/src/comm/LinkInterface.cc +++ b/src/comm/LinkInterface.cc @@ -152,7 +152,9 @@ qint64 LinkInterface::_getCurrentDataRate(int index, const qint64 dataWriteTimes /// Sets the mavlink channel to use for this link void LinkInterface::_setMavlinkChannel(uint8_t channel) { - Q_ASSERT(!_mavlinkChannelSet); + if (_mavlinkChannelSet) { + qWarning() << "Mavlink channel set multiple times"; + } _mavlinkChannelSet = true; _mavlinkChannel = channel; } diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index ff5350a53dfcd5c95cd029532d82e7865912d710..066478eba2cd61953e81ae2b8a26a0d18518692d 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -26,7 +26,7 @@ #endif #ifndef __mobile__ - #include "GPSManager.h" +#include "GPSManager.h" #endif QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog") @@ -69,10 +69,10 @@ LinkManager::~LinkManager() void LinkManager::setToolbox(QGCToolbox *toolbox) { - QGCTool::setToolbox(toolbox); + QGCTool::setToolbox(toolbox); - _autoConnectSettings = toolbox->settingsManager()->autoConnectSettings(); - _mavlinkProtocol = _toolbox->mavlinkProtocol(); + _autoConnectSettings = toolbox->settingsManager()->autoConnectSettings(); + _mavlinkProtocol = _toolbox->mavlinkProtocol(); connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks); _portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass @@ -99,45 +99,45 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer& LinkInterface* pLink = NULL; switch(config->type()) { #ifndef NO_SERIAL_LINK - case LinkConfiguration::TypeSerial: - { - SerialConfiguration* serialConfig = dynamic_cast(config.data()); - if (serialConfig) { - pLink = new SerialLink(config); - if (serialConfig->usbDirect()) { - _activeLinkCheckList.append((SerialLink*)pLink); - if (!_activeLinkCheckTimer.isActive()) { - _activeLinkCheckTimer.start(); - } + case LinkConfiguration::TypeSerial: + { + SerialConfiguration* serialConfig = dynamic_cast(config.data()); + if (serialConfig) { + pLink = new SerialLink(config); + if (serialConfig->usbDirect()) { + _activeLinkCheckList.append((SerialLink*)pLink); + if (!_activeLinkCheckTimer.isActive()) { + _activeLinkCheckTimer.start(); } } } + } break; #endif - case LinkConfiguration::TypeUdp: - pLink = new UDPLink(config); - break; - case LinkConfiguration::TypeTcp: - pLink = new TCPLink(config); - break; + case LinkConfiguration::TypeUdp: + pLink = new UDPLink(config); + break; + case LinkConfiguration::TypeTcp: + pLink = new TCPLink(config); + break; #ifdef QGC_ENABLE_BLUETOOTH - case LinkConfiguration::TypeBluetooth: - pLink = new BluetoothLink(config); - break; + case LinkConfiguration::TypeBluetooth: + pLink = new BluetoothLink(config); + break; #endif #ifndef __mobile__ - case LinkConfiguration::TypeLogReplay: - pLink = new LogReplayLink(config); - break; + case LinkConfiguration::TypeLogReplay: + pLink = new LogReplayLink(config); + break; #endif #ifdef QT_DEBUG - case LinkConfiguration::TypeMock: - pLink = new MockLink(config); - break; + case LinkConfiguration::TypeMock: + pLink = new MockLink(config); + break; #endif - case LinkConfiguration::TypeLast: - default: - break; + case LinkConfiguration::TypeLast: + default: + break; } if (pLink) { @@ -150,11 +150,15 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer& LinkInterface* LinkManager::createConnectedLink(const QString& name) { - Q_ASSERT(name.isEmpty() == false); - for(int i = 0; i < _sharedConfigurations.count(); i++) { - SharedLinkConfigurationPointer& conf = _sharedConfigurations[i]; - if (conf->name() == name) - return createConnectedLink(conf); + if (name.isEmpty()) { + qWarning() << "Internal error"; + } else { + for(int i = 0; i < _sharedConfigurations.count(); i++) { + SharedLinkConfigurationPointer& conf = _sharedConfigurations[i]; + if (conf->name() == name) { + return createConnectedLink(conf); + } + } } return NULL; } @@ -219,13 +223,15 @@ void LinkManager::disconnectAll(void) bool LinkManager::connectLink(LinkInterface* link) { - Q_ASSERT(link); - - if (_connectionsSuspendedMsg()) { + if (link) { + if (_connectionsSuspendedMsg()) { + return false; + } + return link->_connect(); + } else { + qWarning() << "Internal error"; return false; } - - return link->_connect(); } void LinkManager::disconnectLink(LinkInterface* link) @@ -301,7 +307,6 @@ void LinkManager::setConnectionsSuspended(QString reason) { _connectionsSuspended = true; _connectionsSuspendedReason = reason; - Q_ASSERT(!reason.isEmpty()); } void LinkManager::_linkConnected(void) @@ -372,34 +377,34 @@ void LinkManager::loadLinkConfigurationList() bool autoConnect = settings.value(root + "/auto").toBool(); switch((LinkConfiguration::LinkType)type) { #ifndef NO_SERIAL_LINK - case LinkConfiguration::TypeSerial: - pLink = (LinkConfiguration*)new SerialConfiguration(name); - break; + case LinkConfiguration::TypeSerial: + pLink = (LinkConfiguration*)new SerialConfiguration(name); + break; #endif - case LinkConfiguration::TypeUdp: - pLink = (LinkConfiguration*)new UDPConfiguration(name); - break; - case LinkConfiguration::TypeTcp: - pLink = (LinkConfiguration*)new TCPConfiguration(name); - break; + case LinkConfiguration::TypeUdp: + pLink = (LinkConfiguration*)new UDPConfiguration(name); + break; + case LinkConfiguration::TypeTcp: + pLink = (LinkConfiguration*)new TCPConfiguration(name); + break; #ifdef QGC_ENABLE_BLUETOOTH - case LinkConfiguration::TypeBluetooth: - pLink = (LinkConfiguration*)new BluetoothConfiguration(name); - break; + case LinkConfiguration::TypeBluetooth: + pLink = (LinkConfiguration*)new BluetoothConfiguration(name); + break; #endif #ifndef __mobile__ - case LinkConfiguration::TypeLogReplay: - pLink = (LinkConfiguration*)new LogReplayLinkConfiguration(name); - break; + case LinkConfiguration::TypeLogReplay: + pLink = (LinkConfiguration*)new LogReplayLinkConfiguration(name); + break; #endif #ifdef QT_DEBUG - case LinkConfiguration::TypeMock: - pLink = (LinkConfiguration*)new MockConfiguration(name); - break; + case LinkConfiguration::TypeMock: + pLink = (LinkConfiguration*)new MockConfiguration(name); + break; #endif - default: - case LinkConfiguration::TypeLast: - break; + default: + case LinkConfiguration::TypeLast: + break; } if(pLink) { //-- Have the instance load its own values @@ -469,7 +474,7 @@ void LinkManager::_updateAutoConnectLinks(void) qCDebug(LinkManagerLog) << "New auto-connect UDP port added"; UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName); udpConfig->setLocalPort(QGC_UDP_LOCAL_PORT); - udpConfig->setDynamic(true); + udpConfig->setDynamic(true); SharedLinkConfigurationPointer config = addConfiguration(udpConfig); createConnectedLink(config); emit linkConfigurationsChanged(); @@ -647,7 +652,9 @@ QStringList LinkManager::linkTypeStrings(void) const #ifndef __mobile__ list += "Log Replay"; #endif - Q_ASSERT(list.size() == (int)LinkConfiguration::TypeLast); + if (list.size() != (int)LinkConfiguration::TypeLast) { + qWarning() << "Internal error"; + } } return list; } @@ -697,24 +704,29 @@ QStringList LinkManager::serialBaudRates(void) bool LinkManager::endConfigurationEditing(LinkConfiguration* config, LinkConfiguration* editedConfig) { - Q_ASSERT(config != NULL); - Q_ASSERT(editedConfig != NULL); - _fixUnnamed(editedConfig); - config->copyFrom(editedConfig); - saveLinkConfigurationList(); - // Tell link about changes (if any) - config->updateSettings(); - // Discard temporary duplicate - delete editedConfig; + if (config && editedConfig) { + _fixUnnamed(editedConfig); + config->copyFrom(editedConfig); + saveLinkConfigurationList(); + // Tell link about changes (if any) + config->updateSettings(); + // Discard temporary duplicate + delete editedConfig; + } else { + qWarning() << "Internal error"; + } return true; } bool LinkManager::endCreateConfiguration(LinkConfiguration* config) { - Q_ASSERT(config != NULL); - _fixUnnamed(config); - addConfiguration(config); - saveLinkConfigurationList(); + if (config) { + _fixUnnamed(config); + addConfiguration(config); + saveLinkConfigurationList(); + } else { + qWarning() << "Internal error"; + } return true; } @@ -729,21 +741,25 @@ LinkConfiguration* LinkManager::createConfiguration(int type, const QString& nam LinkConfiguration* LinkManager::startConfigurationEditing(LinkConfiguration* config) { - Q_ASSERT(config != NULL); + if (config) { #ifndef NO_SERIAL_LINK - if(config->type() == LinkConfiguration::TypeSerial) - _updateSerialPorts(); + if(config->type() == LinkConfiguration::TypeSerial) + _updateSerialPorts(); #endif - return LinkConfiguration::duplicateSettings(config); + return LinkConfiguration::duplicateSettings(config); + } else { + qWarning() << "Internal error"; + return NULL; + } } void LinkManager::_fixUnnamed(LinkConfiguration* config) { - Q_ASSERT(config != NULL); - //-- Check for "Unnamed" - if (config->name() == "Unnamed") { - switch(config->type()) { + if (config) { + //-- Check for "Unnamed" + if (config->name() == "Unnamed") { + switch(config->type()) { #ifndef NO_SERIAL_LINK case LinkConfiguration::TypeSerial: { QString tname = dynamic_cast(config)->portName(); @@ -755,61 +771,67 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config) #endif config->setName(QString("Serial Device on %1").arg(tname)); break; - } + } #endif case LinkConfiguration::TypeUdp: config->setName( - QString("UDP Link on Port %1").arg(dynamic_cast(config)->localPort())); + QString("UDP Link on Port %1").arg(dynamic_cast(config)->localPort())); break; case LinkConfiguration::TypeTcp: { - TCPConfiguration* tconfig = dynamic_cast(config); - if(tconfig) { - config->setName( - QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg((int)tconfig->port())); - } + TCPConfiguration* tconfig = dynamic_cast(config); + if(tconfig) { + config->setName( + QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg((int)tconfig->port())); } + } break; #ifdef QGC_ENABLE_BLUETOOTH case LinkConfiguration::TypeBluetooth: { - BluetoothConfiguration* tconfig = dynamic_cast(config); - if(tconfig) { - config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name)); - } + BluetoothConfiguration* tconfig = dynamic_cast(config); + if(tconfig) { + config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name)); } + } break; #endif #ifndef __mobile__ case LinkConfiguration::TypeLogReplay: { - LogReplayLinkConfiguration* tconfig = dynamic_cast(config); - if(tconfig) { - config->setName(QString("Log Replay %1").arg(tconfig->logFilenameShort())); - } + LogReplayLinkConfiguration* tconfig = dynamic_cast(config); + if(tconfig) { + config->setName(QString("Log Replay %1").arg(tconfig->logFilenameShort())); } + } break; #endif #ifdef QT_DEBUG case LinkConfiguration::TypeMock: config->setName( - QString("Mock Link")); + QString("Mock Link")); break; #endif case LinkConfiguration::TypeLast: default: break; + } } + } else { + qWarning() << "Internal error"; } } void LinkManager::removeConfiguration(LinkConfiguration* config) { - Q_ASSERT(config != NULL); - LinkInterface* iface = config->link(); - if(iface) { - disconnectLink(iface); - } + if (config) { + LinkInterface* iface = config->link(); + if(iface) { + disconnectLink(iface); + } - _removeConfiguration(config); - saveLinkConfigurationList(); + _removeConfiguration(config); + saveLinkConfigurationList(); + } else { + qWarning() << "Internal error"; + } } bool LinkManager::isAutoconnectLink(LinkInterface* link) diff --git a/src/comm/LogReplayLink.cc b/src/comm/LogReplayLink.cc index 1fc8e73e16145114d7365c4678b9dc831b3f5153..8bbe32dd078c487911ff2f39a47e6beff965b034 100644 --- a/src/comm/LogReplayLink.cc +++ b/src/comm/LogReplayLink.cc @@ -35,8 +35,11 @@ void LogReplayLinkConfiguration::copyFrom(LinkConfiguration *source) { LinkConfiguration::copyFrom(source); LogReplayLinkConfiguration* ssource = dynamic_cast(source); - Q_ASSERT(ssource != NULL); - _logFilename = ssource->logFilename(); + if (ssource) { + _logFilename = ssource->logFilename(); + } else { + qWarning() << "Internal error"; + } } void LogReplayLinkConfiguration::saveSettings(QSettings& settings, const QString& root) @@ -70,7 +73,9 @@ LogReplayLink::LogReplayLink(SharedLinkConfigurationPointer& config) , _connected(false) , _replayAccelerationFactor(1.0f) { - Q_ASSERT(_logReplayConfig); + if (!_logReplayConfig) { + qWarning() << "Internal error"; + } _readTickTimer.moveToThread(this); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 9e600db18d1256be835e7a0af4e8dba02d3b96f7..4719c33e940466380ca528d3f94004f408e17519 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -38,10 +38,13 @@ SerialLink::SerialLink(SharedLinkConfigurationPointer& config) , _reqReset(false) , _serialConfig(qobject_cast(config.data())) { - Q_ASSERT(_serialConfig); + if (!_serialConfig) { + qWarning() << "Internal error"; + return; + } qCDebug(SerialLinkLog) << "Create SerialLink " << _serialConfig->portName() << _serialConfig->baud() << _serialConfig->flowControl() - << _serialConfig->parity() << _serialConfig->dataBits() << _serialConfig->stopBits(); + << _serialConfig->parity() << _serialConfig->dataBits() << _serialConfig->stopBits(); qCDebug(SerialLinkLog) << "portName: " << _serialConfig->portName(); } @@ -76,7 +79,7 @@ bool SerialLink::_isBootloader() info.description().toLower().contains("px4 fmu v1.6"))) { qCDebug(SerialLinkLog) << "BOOTLOADER FOUND"; return true; - } + } } // Not found return false; @@ -229,7 +232,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& emit connected(); qCDebug(SerialLinkLog) << "Connection SeriaLink: " << "with settings" << _serialConfig->portName() - << _serialConfig->baud() << _serialConfig->dataBits() << _serialConfig->parity() << _serialConfig->stopBits(); + << _serialConfig->baud() << _serialConfig->dataBits() << _serialConfig->parity() << _serialConfig->stopBits(); return true; // successful connection } @@ -299,34 +302,34 @@ qint64 SerialLink::getConnectionSpeed() const qint64 dataRate; switch (baudRate) { - case QSerialPort::Baud1200: - dataRate = 1200; - break; - case QSerialPort::Baud2400: - dataRate = 2400; - break; - case QSerialPort::Baud4800: - dataRate = 4800; - break; - case QSerialPort::Baud9600: - dataRate = 9600; - break; - case QSerialPort::Baud19200: - dataRate = 19200; - break; - case QSerialPort::Baud38400: - dataRate = 38400; - break; - case QSerialPort::Baud57600: - dataRate = 57600; - break; - case QSerialPort::Baud115200: - dataRate = 115200; - break; - // Otherwise do nothing. - default: - dataRate = -1; - break; + case QSerialPort::Baud1200: + dataRate = 1200; + break; + case QSerialPort::Baud2400: + dataRate = 2400; + break; + case QSerialPort::Baud4800: + dataRate = 4800; + break; + case QSerialPort::Baud9600: + dataRate = 9600; + break; + case QSerialPort::Baud19200: + dataRate = 19200; + break; + case QSerialPort::Baud38400: + dataRate = 38400; + break; + case QSerialPort::Baud57600: + dataRate = 57600; + break; + case QSerialPort::Baud115200: + dataRate = 115200; + break; + // Otherwise do nothing. + default: + dataRate = -1; + break; } return dataRate; } @@ -378,15 +381,18 @@ void SerialConfiguration::copyFrom(LinkConfiguration *source) { LinkConfiguration::copyFrom(source); SerialConfiguration* ssource = dynamic_cast(source); - Q_ASSERT(ssource != NULL); - _baud = ssource->baud(); - _flowControl = ssource->flowControl(); - _parity = ssource->parity(); - _dataBits = ssource->dataBits(); - _stopBits = ssource->stopBits(); - _portName = ssource->portName(); - _portDisplayName = ssource->portDisplayName(); - _usbDirect = ssource->_usbDirect; + if (ssource) { + _baud = ssource->baud(); + _flowControl = ssource->flowControl(); + _parity = ssource->parity(); + _dataBits = ssource->dataBits(); + _stopBits = ssource->stopBits(); + _portName = ssource->portName(); + _portDisplayName = ssource->portDisplayName(); + _usbDirect = ssource->_usbDirect; + } else { + qWarning() << "Internal error"; + } } void SerialConfiguration::updateSettings() diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index a286a078a05022a00af20213ff8df687cb0370f9..a0810ba566b76994777a8cd12895cbfd78255963 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -67,15 +67,17 @@ static QString get_ip_address(const QString& address) UDPLink::UDPLink(SharedLinkConfigurationPointer& config) : LinkInterface(config) -#if defined(QGC_ZEROCONF_ENABLED) + #if defined(QGC_ZEROCONF_ENABLED) , _dnssServiceRef(NULL) -#endif + #endif , _running(false) , _socket(NULL) , _udpConfig(qobject_cast(config.data())) , _connectState(false) { - Q_ASSERT(_udpConfig); + if (!_udpConfig) { + qWarning() << "Internal error"; + } moveToThread(this); } @@ -292,14 +294,14 @@ void UDPLink::_registerZeroconf(uint16_t port, const std::string ®Type) { #if defined(QGC_ZEROCONF_ENABLED) DNSServiceErrorType result = DNSServiceRegister(&_dnssServiceRef, 0, 0, 0, - regType.c_str(), - NULL, - NULL, - htons(port), - 0, - NULL, - NULL, - NULL); + regType.c_str(), + NULL, + NULL, + htons(port), + 0, + NULL, + NULL, + NULL); if (result != kDNSServiceErr_NoError) { emit communicationError("UDP Link Error", "Error registering Zeroconf"); @@ -315,10 +317,10 @@ void UDPLink::_deregisterZeroconf() { #if defined(QGC_ZEROCONF_ENABLED) if (_dnssServiceRef) - { - DNSServiceRefDeallocate(_dnssServiceRef); - _dnssServiceRef = NULL; - } + { + DNSServiceRefDeallocate(_dnssServiceRef); + _dnssServiceRef = NULL; + } #endif } @@ -347,15 +349,18 @@ void UDPConfiguration::copyFrom(LinkConfiguration *source) { LinkConfiguration::copyFrom(source); UDPConfiguration* usource = dynamic_cast(source); - Q_ASSERT(usource != NULL); - _localPort = usource->localPort(); - _hosts.clear(); - QString host; - int port; - if(usource->firstHost(host, port)) { - do { - addHost(host, port); - } while(usource->nextHost(host, port)); + if (usource) { + _localPort = usource->localPort(); + _hosts.clear(); + QString host; + int port; + if(usource->firstHost(host, port)) { + do { + addHost(host, port); + } while(usource->nextHost(host, port)); + } + } else { + qWarning() << "Internal error"; } } diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 67621b33b234d9757f3e593cfb4407ef889e45d8..87cef32ba6d58cd364de6be41bd0f5b2bd2db328 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -92,10 +92,7 @@ static MainWindow* _instance = NULL; ///< @brief MainWindow singleton MainWindow* MainWindow::_create() { - Q_ASSERT(_instance == NULL); new MainWindow(); - // _instance is set in constructor - Q_ASSERT(_instance); return _instance; } @@ -118,7 +115,6 @@ MainWindow::MainWindow() , _mainQmlWidgetHolder(NULL) , _forceClose(false) { - Q_ASSERT(_instance == NULL); _instance = this; //-- Load fonts @@ -337,7 +333,7 @@ void MainWindow::_showDockWidget(const QString& name, bool show) // Create the inner widget if we need to if (!_mapName2DockWidget.contains(name)) { if(!_createInnerDockWidget(name)) { - qWarning() << "Trying to load non existing widget:" << name; + qWarning() << "Trying to load non existent widget:" << name; return; } }