Commit f17a103b authored by DonLakeFlyer's avatar DonLakeFlyer

Q_ASSERT cleanup

parent 59f230ba
......@@ -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()) {
......
......@@ -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<VehicleComponent*>(qvariant_cast<QObject *>(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<VehicleComponent*>(qvariant_cast<QObject *>(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)
......
......@@ -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)
......
......@@ -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; i<cMavTypes; i++) {
Q_ASSERT(mavTypeInfo[i].type == mavTypes[i]);
}
#endif
}
QString AirframeComponent::name(void) const
......
......@@ -57,7 +57,9 @@ AirframeComponentController::AirframeComponentController(void) :
Q_CHECK_PTR(pInfo);
if (_autostartId == pInfo->autostartId) {
Q_ASSERT(!autostartFound);
if (autostartFound) {
qWarning() << "AirframeComponentController::AirframeComponentController duplicate ids found:" << _autostartId;
}
autostartFound = true;
_currentAirframeType = pType->name;
_currentVehicleName = pInfo->name;
......
......@@ -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";
......
......@@ -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";
}
}
......
......@@ -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();
......
......@@ -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<Fact*>();
Q_ASSERT(fact);
fact->_containerSetRawValue(value);
Fact* fact = NULL;
if (_mapParameterName2Variant[componentId].contains(parameterName)) {
fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
}
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<Fact*>(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();
......
......@@ -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;
......
......@@ -28,8 +28,6 @@ GPSManager::~GPSManager()
void GPSManager::connectGPS(const QString& device)
{
Q_ASSERT(_toolbox);
RTKSettings* rtkSettings = qgcApp()->toolbox()->settingsManager()->rtkSettings();
cleanup();
......
......@@ -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()
......
......@@ -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
......
......@@ -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)
......
......@@ -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;
}
}
......@@ -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
}
......
......@@ -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<MAVLinkLogFiles*>(_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<MAVLinkLogFiles*>(_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<MAVLinkLogFiles*>(_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) {
......
......@@ -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<QQuickItem*>(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<QQuickItem*>(component.create(context));
Q_ASSERT(item);
item->setParentItem(parent);
item->setProperty("vehicleComponent", QVariant::fromValue(this));
}
void VehicleComponent::setupTriggerSignals(void)
......
......@@ -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());
}
......@@ -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;
}
......@@ -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<SerialConfiguration*>(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<SerialConfiguration*>(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<SerialConfiguration*>(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<UDPConfiguration*>(config)->localPort()));
QString("UDP Link on Port %1").arg(dynamic_cast<UDPConfiguration*>(config)->localPort()));
break;
case LinkConfiguration::TypeTcp: {
TCPConfiguration* tconfig = dynamic_cast<TCPConfiguration*>(config);
if(tconfig) {
config->setName(
QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg((int)tconfig->port()));
}
TCPConfiguration* tconfig = dynamic_cast<TCPConfiguration*>(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<BluetoothConfiguration*>(config);
if(tconfig) {
config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name));
}
BluetoothConfiguration* tconfig = dynamic_cast<BluetoothConfiguration*>(config);
if(tconfig) {
config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name));
}
}
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay: {
LogReplayLinkConfiguration* tconfig = dynamic_cast<LogReplayLinkConfiguration*>(config);
if(tconfig) {
config->setName(QString("Log Replay %1").arg(tconfig->logFilenameShort()));
}
LogReplayLinkConfiguration* tconfig = dynamic_cast<LogReplayLinkConfiguration*>(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)
......
......@@ -35,8 +35,11 @@ void LogReplayLinkConfiguration::copyFrom(LinkConfiguration *source)
{
LinkConfiguration::copyFrom(source);
LogReplayLinkConfiguration* ssource = dynamic_cast<LogReplayLinkConfiguration*>(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);
......
......@@ -38,10 +38,13 @@ SerialLink::SerialLink(SharedLinkConfigurationPointer& config)
, _reqReset(false)
, _serialConfig(qobject_cast<SerialConfiguration*>(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<SerialConfiguration*>(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()
......
......@@ -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<UDPConfiguration*>(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 &regType)
{
#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<UDPConfiguration*>(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";
}
}
......
......@@ -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;
}
}
......
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