Commit 6e57a50a authored by Don Gagne's avatar Don Gagne Committed by GitHub
Browse files

Merge pull request #5073 from DonLakeFlyer/Fixes

Pile of fixes
parents 23f21402 6d83753f
......@@ -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";
}
}
......
......@@ -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
}
......
......@@ -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;
......
......@@ -245,9 +245,9 @@ FlightMap {
}
}
// Camera points
// Camera trigger points
MapItemView {
model: _missionController.cameraPoints
model: _activeVehicle ? _activeVehicle.cameraTriggerPoints : 0
delegate: CameraTriggerIndicator {
coordinate: object.coordinate
......
......@@ -28,8 +28,6 @@ GPSManager::~GPSManager()
void GPSManager::connectGPS(const QString& device)
{
Q_ASSERT(_toolbox);
RTKSettings* rtkSettings = qgcApp()->toolbox()->settingsManager()->rtkSettings();
cleanup();
......
......@@ -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)) {
......
......@@ -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;
......
......@@ -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;
}
}
......
......@@ -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);
......
......@@ -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()
......
......@@ -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
......
Supports Markdown
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