Commit a9a17e88 authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'mavlink/master' into flightView

* mavlink/master:
  update android version
  qmake cleanup git version
  travis-ci enable ccache for linux
  travis-ci switch linux to container infrastructure
  travis-ci disable android debug
  Fix mode selection coloring
  Fix binding loop
  Decimal place support from meta data
  Fix item dragging
  Fix home position handling
  Fix signalling
  Decimal place support from meta data
  Fix item dragging
  Fix home position handling
  Fix signalling
  Move ParameterLoader override to FirmwarePlugin
parents 232cd4a1 579206c6
......@@ -13,20 +13,20 @@ matrix:
include:
- os: linux
env: SPEC=linux-g++-64 CONFIG=debug
sudo: true
sudo: false
- os: linux
env: SPEC=linux-g++-64 CONFIG=installer
sudo: true
sudo: false
- os: osx
osx_image: xcode7
env: SPEC=macx-clang CONFIG=debug
- os: osx
osx_image: xcode7
env: SPEC=macx-clang CONFIG=installer
- os: android
language: android
env: SPEC=android-g++ CONFIG=debug
sudo: false
# - os: android
# language: android
# env: SPEC=android-g++ CONFIG=debug
# sudo: false
- os: android
language: android
env: SPEC=android-g++ CONFIG=installer
......@@ -38,8 +38,25 @@ android:
- build-tools-21.1.1
- android-21
addons:
apt:
sources:
- ubuntu-toolchain-r-test
packages:
- ccache
- espeak
- g++-4.8
- gcc-4.8
- libc6-i386
- libespeak-dev
- libopenscenegraph-dev
- libsdl1.2-dev
- libudev-dev
cache:
- apt
directories:
- $HOME/.ccache
before_install:
- cd ${TRAVIS_BUILD_DIR} && git fetch --unshallow && git fetch --tags
......@@ -49,10 +66,7 @@ before_install:
install:
- if [ "${TRAVIS_OS_NAME}" = "linux" ]; then
sudo apt-add-repository -y ppa:ubuntu-toolchain-r/test
&& sudo apt-get -qq update
&& sudo apt-get -qq install g++-4.8 espeak libespeak-dev libopenscenegraph-dev libsdl1.2-dev libudev-dev
&& wget https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.5.1-linux.tar.bz2
wget https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.5.1-linux.tar.bz2
&& tar jxf Qt5.5.1-linux.tar.bz2 -C /tmp
&& export PATH=/tmp/Qt/5.5/gcc_64/bin:$PATH
&& export CXX="g++-4.8"
......@@ -80,6 +94,13 @@ install:
before_script:
# setup ccache
- mkdir -p ~/bin
- ln -s /usr/bin/ccache ~/bin/g++
- ln -s /usr/bin/ccache ~/bin/g++-4.8
- ln -s /usr/bin/ccache ~/bin/gcc
- ln -s /usr/bin/ccache ~/bin/gcc-4.8
- export PATH=~/bin:$PATH
- if [[ "${TRAVIS_OS_NAME}" = "android" && "${CONFIG}" = "installer" && -z ${ANDROID_STOREPASS} ]]; then export CONFIG=release; fi
- qmake -r qgroundcontrol.pro CONFIG+=${CONFIG} CONFIG+=WarningsAsErrorsOn -spec ${SPEC}
......
......@@ -507,8 +507,8 @@ INCLUDEPATH += \
HEADERS+= \
src/AutoPilotPlugins/AutoPilotPlugin.h \
src/AutoPilotPlugins/AutoPilotPluginManager.h \
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \
src/AutoPilotPlugins/Generic/GenericParameterFacts.h \
src/AutoPilotPlugins/PX4/AirframeComponent.h \
src/AutoPilotPlugins/PX4/AirframeComponentAirframes.h \
src/AutoPilotPlugins/PX4/AirframeComponentController.h \
......@@ -518,7 +518,6 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/PowerComponentController.h \
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h \
src/AutoPilotPlugins/PX4/PX4Component.h \
src/AutoPilotPlugins/PX4/PX4ParameterLoader.h \
src/AutoPilotPlugins/PX4/RadioComponent.h \
src/AutoPilotPlugins/PX4/RadioComponentController.h \
src/AutoPilotPlugins/PX4/SafetyComponent.h \
......@@ -527,11 +526,14 @@ HEADERS+= \
src/FirmwarePlugin/FirmwarePluginManager.h \
src/FirmwarePlugin/FirmwarePlugin.h \
src/FirmwarePlugin/APM/APMFirmwarePlugin.h \
src/FirmwarePlugin/APM/APMParameterLoader.h \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericParameterLoader.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4ParameterLoader.h \
src/Vehicle/MultiVehicleManager.h \
src/Vehicle/Vehicle.h \
src/VehicleSetup/VehicleComponent.h \
......@@ -548,8 +550,8 @@ HEADERS += \
SOURCES += \
src/AutoPilotPlugins/AutoPilotPlugin.cc \
src/AutoPilotPlugins/AutoPilotPluginManager.cc \
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \
src/AutoPilotPlugins/Generic/GenericParameterFacts.cc \
src/AutoPilotPlugins/PX4/AirframeComponent.cc \
src/AutoPilotPlugins/PX4/AirframeComponentAirframes.cc \
src/AutoPilotPlugins/PX4/AirframeComponentController.cc \
......@@ -559,19 +561,21 @@ SOURCES += \
src/AutoPilotPlugins/PX4/PowerComponentController.cc \
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc \
src/AutoPilotPlugins/PX4/PX4Component.cc \
src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc \
src/AutoPilotPlugins/PX4/RadioComponent.cc \
src/AutoPilotPlugins/PX4/RadioComponentController.cc \
src/AutoPilotPlugins/PX4/SafetyComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \
src/FirmwarePlugin/APM/APMParameterLoader.cc \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/Generic/GenericParameterLoader.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4ParameterLoader.cc \
src/Vehicle/MultiVehicleManager.cc \
src/Vehicle/Vehicle.cc \
src/VehicleSetup/VehicleComponent.cc \
......
......@@ -73,6 +73,7 @@ MobileBuild {
exists ($$PWD/.git) {
GIT_DESCRIBE = $$system(git --git-dir $$PWD/.git --work-tree $$PWD describe --always --tags)
message(QGroundControl version $${GIT_DESCRIBE})
} else {
GIT_DESCRIBE = None
}
......
<?xml version="1.0"?>
<manifest package="org.mavlink.qgroundcontrol" xmlns:android="http://schemas.android.com/apk/res/android" android:versionName="2.7.1-555-g8aa592d" android:versionCode="7" android:installLocation="auto">
<manifest package="org.mavlink.qgroundcontrol" xmlns:android="http://schemas.android.com/apk/res/android" android:versionName="2.7.1-668-g4ad2975" android:versionCode="8" android:installLocation="auto">
<application android:hardwareAccelerated="true" android:name="org.qtproject.qt5.android.bindings.QtApplication" android:label="-- %%INSERT_APP_NAME%% --" android:icon="@drawable/icon">
<activity android:configChanges="orientation|uiMode|screenLayout|screenSize|smallestScreenSize|locale|fontScale|keyboard|keyboardHidden|navigation" android:name="org.qgroundcontrol.qgchelper.UsbDeviceJNI" android:label="-- %%INSERT_APP_NAME%% --" android:screenOrientation="sensorLandscape" android:launchMode="singleTask">
<intent-filter>
......
......@@ -30,6 +30,3 @@ message(Qt version $$[QT_VERSION])
error("Unsupported Qt version, 5.4+ is required")
}
message(QGroundControl version $${GIT_DESCRIBE})
git_ver.commands = $$QGC_GIT_VER
QMAKE_EXTRA_TARGETS += git_ver
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "APMAutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "QGCMessageBox.h"
#include "UAS.h"
#include "FirmwarePlugin/APM/APMParameterLoader.h" // FIXME: Hack
#include "FirmwarePlugin/APM/APMFirmwarePlugin.h" // FIXME: Hack
/// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type.
APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent),
_incorrectParameterVersion(false)
{
Q_ASSERT(vehicle);
// This kicks off parameter load
_firmwarePlugin->getParameterLoader(this, vehicle);
}
APMAutoPilotPlugin::~APMAutoPilotPlugin()
{
}
void APMAutoPilotPlugin::clearStaticData(void)
{
APMParameterLoader::clearStaticData();
}
const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
{
static const QVariantList emptyList;
return emptyList;
}
/// This will perform various checks prior to signalling that the plug in ready
void APMAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
{
#if 0
I believe APM has parameter version stamp, we should check that
// Check for older parameter version set
// FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp
// should be used instead.
if (parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF")) {
_incorrectParameterVersion = true;
QGCMessageBox::warning("Setup", "This version of GroundControl can only perform vehicle setup on a newer version of firmware. "
"Please perform a Firmware Upgrade if you wish to use Vehicle Setup.");
}
#endif
_parametersReady = true;
_missingParameters = missingParameters;
emit missingParametersChanged(_missingParameters);
emit parametersReadyChanged(_parametersReady);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef APMAutoPilotPlugin_H
#define APMAutoPilotPlugin_H
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
/// This is the APM specific implementation of the AutoPilot class.
class APMAutoPilotPlugin : public AutoPilotPlugin
{
Q_OBJECT
public:
APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~APMAutoPilotPlugin();
// Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void);
static void clearStaticData(void);
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
private:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
};
#endif
......@@ -30,10 +30,12 @@
#include "MainWindow.h"
#include "ParameterLoader.h"
#include "UAS.h"
#include "FirmwarePlugin.h"
AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _firmwarePlugin(vehicle->firmwarePlugin())
, _parametersReady(false)
, _missingParameters(false)
, _setupComplete(false)
......@@ -107,34 +109,34 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void)
void AutoPilotPlugin::refreshAllParameters(void)
{
_getParameterLoader()->refreshAllParameters();
_firmwarePlugin->getParameterLoader(this, _vehicle)->refreshAllParameters();
}
void AutoPilotPlugin::refreshParameter(int componentId, const QString& name)
{
_getParameterLoader()->refreshParameter(componentId, name);
_firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParameter(componentId, name);
}
void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
_getParameterLoader()->refreshParametersPrefix(componentId, namePrefix);
_firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParametersPrefix(componentId, namePrefix);
}
bool AutoPilotPlugin::parameterExists(int componentId, const QString& name)
{
return _getParameterLoader()->parameterExists(componentId, name);
return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name);
}
Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name)
{
return _getParameterLoader()->getFact(componentId, name);
return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name);
}
bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{
switch (provider) {
case FactSystem::ParameterProvider:
return _getParameterLoader()->parameterExists(componentId, name);
return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name);
// Other providers will go here once they come online
}
......@@ -147,7 +149,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
{
switch (provider) {
case FactSystem::ParameterProvider:
return _getParameterLoader()->getFact(componentId, name);
return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name);
// Other providers will go here once they come online
}
......@@ -158,20 +160,20 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
QStringList AutoPilotPlugin::parameterNames(int componentId)
{
return _getParameterLoader()->parameterNames(componentId);
return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterNames(componentId);
}
const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
{
return _getParameterLoader()->getGroupMap();
return _firmwarePlugin->getParameterLoader(this, _vehicle)->getGroupMap();
}
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
_getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName());
_firmwarePlugin->getParameterLoader(this, _vehicle)->writeParametersToStream(stream, _vehicle->uas()->getUASName());
}
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{
return _getParameterLoader()->readParametersFromStream(stream);
return _firmwarePlugin->getParameterLoader(this, _vehicle)->readParametersFromStream(stream);
}
......@@ -38,6 +38,7 @@
class ParameterLoader;
class Vehicle;
class FirmwarePlugin;
/// This is the base class for AutoPilot plugins
///
......@@ -132,20 +133,18 @@ protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
/// Returns the ParameterLoader
virtual ParameterLoader* _getParameterLoader(void) = 0;
Vehicle* _vehicle;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete;
Vehicle* _vehicle;
FirmwarePlugin* _firmwarePlugin;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete;
private slots:
void _uasDisconnected(void);
void _parametersReadyChanged(bool parametersReady);
private:
void _recalcSetupComplete(void);
void _recalcSetupComplete(void);
};
#endif
......@@ -26,6 +26,7 @@
#include "AutoPilotPluginManager.h"
#include "PX4/PX4AutoPilotPlugin.h"
#include "APM/APMAutoPilotPlugin.h"
#include "Generic/GenericAutoPilotPlugin.h"
IMPLEMENT_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager)
......@@ -44,9 +45,12 @@ AutoPilotPluginManager::~AutoPilotPluginManager()
AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle)
{
if (vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
return new PX4AutoPilotPlugin(vehicle, vehicle);
} else {
return new GenericAutoPilotPlugin(vehicle, vehicle);
switch (vehicle->firmwareType()) {
case MAV_AUTOPILOT_PX4:
return new PX4AutoPilotPlugin(vehicle, vehicle);
case MAV_AUTOPILOT_ARDUPILOTMEGA:
return new APMAutoPilotPlugin(vehicle, vehicle);
default:
return new GenericAutoPilotPlugin(vehicle, vehicle);
}
}
......@@ -25,17 +25,15 @@
/// @author Don Gagne <don@thegagnes.com>
#include "GenericAutoPilotPlugin.h"
#include "FirmwarePlugin/Generic/GenericFirmwarePlugin.h" // FIXME: Hack
GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent)
{
Q_ASSERT(vehicle);
_parameterFacts = new GenericParameterFacts(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReadySlot);
connect(_parameterFacts, &GenericParameterFacts::parameterListProgress, this, &GenericAutoPilotPlugin::parameterListProgress);
// This kicks off parameter load
_firmwarePlugin->getParameterLoader(this, vehicle);
}
void GenericAutoPilotPlugin::clearStaticData(void)
......@@ -50,7 +48,8 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void)
return emptyList;
}
void GenericAutoPilotPlugin::_parametersReadySlot(bool missingParameters)
/// This will perform various checks prior to signalling that the plug in ready
void GenericAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
{
_parametersReady = true;
_missingParameters = missingParameters;
......
......@@ -25,7 +25,6 @@
#define GENERICAUTOPILOT_H
#include "AutoPilotPlugin.h"
#include "GenericParameterFacts.h"
/// @file
/// @brief This is the generic implementation of the AutoPilotPlugin class for mavs
......@@ -44,14 +43,9 @@ public:
static void clearStaticData(void);
private slots:
void _parametersReadySlot(bool missingParameters);
private:
// Overrides from AutoPilotPlugin
virtual ParameterLoader* _getParameterLoader(void) { return _parameterFacts; }
GenericParameterFacts* _parameterFacts;
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
};
#endif
......@@ -260,7 +260,7 @@ QGCView {
thresholdValue: controller.manualModeThreshold
thresholdDragEnabled: false
onModeChannelIndexChanged: controller.manualModeChannelIndex = modeChannelIndex
onModeChannelIndexSelected: controller.manualModeChannelIndex = index
}
ModeSwitchDisplay {
......@@ -308,7 +308,7 @@ QGCView {
thresholdValue: controller.acroModeThreshold
thresholdDragEnabled: true
onModeChannelIndexChanged: controller.acroModeChannelIndex = modeChannelIndex
onModeChannelIndexSelected: controller.acroModeChannelIndex = index
onThresholdValueChanged: controller.acroModeThreshold = thresholdValue
Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } }
......@@ -341,7 +341,7 @@ QGCView {
thresholdValue: controller.posCtlModeThreshold
thresholdDragEnabled: true
onModeChannelIndexChanged: controller.posCtlModeChannelIndex = modeChannelIndex
onModeChannelIndexSelected: controller.posCtlModeChannelIndex = index
onThresholdValueChanged: controller.posCtlModeThreshold = thresholdValue
Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } }
......@@ -374,7 +374,7 @@ QGCView {
thresholdValue: controller.loiterModeThreshold
thresholdDragEnabled: true
onModeChannelIndexChanged: controller.loiterModeChannelIndex = modeChannelIndex
onModeChannelIndexSelected: controller.loiterModeChannelIndex = index
onThresholdValueChanged: controller.loiterModeThreshold = thresholdValue
Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } }
......@@ -391,7 +391,7 @@ QGCView {
thresholdValue: controller.returnModeThreshold
thresholdDragEnabled: true
onModeChannelIndexChanged: controller.returnModeChannelIndex = modeChannelIndex
onModeChannelIndexSelected: controller.returnModeChannelIndex = index
onThresholdValueChanged: controller.returnModeThreshold = thresholdValue
Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } }
......@@ -408,7 +408,7 @@ QGCView {
thresholdValue: controller.offboardModeThreshold
thresholdDragEnabled: true
onModeChannelIndexChanged: controller.offboardModeChannelIndex = modeChannelIndex
onModeChannelIndexSelected: controller.offboardModeChannelIndex = index
onThresholdValueChanged: controller.offboardModeThreshold = thresholdValue
Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } }
......
......@@ -23,12 +23,13 @@
#include "PX4AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "PX4ParameterLoader.h"
#include "PX4AirframeLoader.h"
#include "FlightModesComponentController.h"
#include "AirframeComponentController.h"
#include "QGCMessageBox.h"
#include "UAS.h"
#include "FirmwarePlugin/PX4/PX4ParameterLoader.h" // FIXME: Hack
#include "FirmwarePlugin/PX4/PX4FirmwarePlugin.h" // FIXME: Hack
/// @file
/// @brief This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_PX4 type.
......@@ -66,7 +67,6 @@ union px4_custom_mode {
PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent),
_parameterFacts(NULL),
_airframeComponent(NULL),
_radioComponent(NULL),
_flightModesComponent(NULL),
......@@ -77,22 +77,17 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
{
Q_ASSERT(vehicle);
_parameterFacts = new PX4ParameterLoader(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_parametersReadyPreChecks);
connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress);
_airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this);
Q_CHECK_PTR(_airframeFacts);
PX4ParameterLoader::loadParameterFactMetaData();
PX4AirframeLoader::loadAirframeFactMetaData();
// This kicks off parameter load
_firmwarePlugin->getParameterLoader(this, vehicle);
}
PX4AutoPilotPlugin::~PX4AutoPilotPlugin()
{
delete _parameterFacts;
delete _airframeFacts;
}
......
......@@ -25,7 +25,6 @@
#define PX4AUTOPILOT_H
#include "AutoPilotPlugin.h"
#include "PX4ParameterLoader.h"
#include "PX4AirframeLoader.h"
#include "AirframeComponent.h"
#include "RadioComponent.h"
......@@ -62,14 +61,11 @@ public:
SafetyComponent* safetyComponent(void) { return _safetyComponent; }
PowerComponent* powerComponent(void) { return _powerComponent; }
private slots:
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
private:
// Overrides from AutoPilotPlugin
virtual ParameterLoader* _getParameterLoader(void) { return _parameterFacts; }
PX4ParameterLoader* _parameterFacts;
PX4AirframeLoader* _airframeFacts;
QVariantList _components;
AirframeComponent* _airframeComponent;
......
......@@ -131,7 +131,22 @@ QVariant Fact::value(void) const
QString Fact::valueString(void) const
{
return _value.toString();
QString valueString;
switch (type()) {
case FactMetaData::valueTypeFloat:
qDebug() << name() << value() << decimalPlaces();
valueString = QString("%1").arg(value().toFloat(), 0, 'g', decimalPlaces());
break;
case FactMetaData::valueTypeDouble:
valueString = QString("%1").arg(value().toDouble(), 0, 'g', decimalPlaces());
break;
default:
valueString = value().toString();
break;
}
return valueString;
}
QVariant Fact::defaultValue(void) const
......@@ -222,6 +237,16 @@ bool Fact::maxIsDefaultForType(void) const
}
}
int Fact::decimalPlaces(void) const
{
if (_metaData) {
return _metaData->decimalPlaces();
} else {
qWarning() << "Meta data pointer missing";
return FactMetaData::defaultDecimalPlaces;
}
}
QString Fact::group(void) const
{
if (_metaData) {
......
......@@ -46,22 +46,23 @@ public:
const Fact& operator=(const Fact& other);
Q_PROPERTY(int componentId READ componentId CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(int componentId READ componentId CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
......@@ -86,6 +87,7 @@ public:
QVariant max(void) const;
bool maxIsDefaultForType(void) const;
QString group(void) const;
int decimalPlaces(void) const;
/// Sets and sends new value to vehicle even if value is the same
void forceSetValue(const QVariant& value);
......
......@@ -32,30 +32,32 @@
#include <limits>
FactMetaData::FactMetaData(QObject* parent) :
QObject(parent),
_group("*Default Group"),
_type(valueTypeInt32),
_defaultValue(0),
_defaultValueAvailable(false),
_min(_minForType()),
_max(_maxForType()),
_minIsDefaultForType(true),
_maxIsDefaultForType(true)
FactMetaData::FactMetaData(QObject* parent)
: QObject(parent)
, _group("*Default Group")
, _type(valueTypeInt32)
, _defaultValue(0)
, _defaultValueAvailable(false)
, _min(_minForType())
, _max(_maxForType())
, _minIsDefaultForType(true)
, _maxIsDefaultForType(true)
, _decimalPlaces(defaultDecimalPlaces)
{
}
FactMetaData::FactMetaData(ValueType_t type, QObject* parent) :
QObject(parent),
_group("*Default Group"),
_type(type),
_defaultValue(0),
_defaultValueAvailable(false),
_min(_minForType()),
_max(_maxForType()),
_minIsDefaultForType(true),
_maxIsDefaultForType(true)
FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
: QObject(parent)
, _group("*Default Group")
, _type(type)
, _defaultValue(0)
, _defaultValueAvailable(false)
, _min(_minForType())
, _max(_maxForType())
, _minIsDefaultForType(true)
, _maxIsDefaultForType(true)
, _decimalPlaces(defaultDecimalPlaces)
{
}
......@@ -76,6 +78,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_max = other._max;
_minIsDefaultForType = other._minIsDefaultForType;
_maxIsDefaultForType = other._maxIsDefaultForType;
_decimalPlaces = other._decimalPlaces;
return *this;
}
......
......@@ -59,18 +59,19 @@ public:
const FactMetaData& operator=(const FactMetaData& other);
// Property accessors
QString name(void) const { return _name; }
QString group(void) const { return _group; }
ValueType_t type(void) const { return _type; }
QString name(void) const { return _name; }
QString group(void) const { return _group; }
ValueType_t type(void) const { return _type; }
QVariant defaultValue(void) const;
bool defaultValueAvailable(void) const { return _defaultValueAvailable; }
QString shortDescription(void) const { return _shortDescription; }
QString longDescription(void) const { return _longDescription;}
QString units(void) const { return _units; }
QVariant min(void) const { return _min; }
QVariant max(void) const { return _max; }
bool minIsDefaultForType(void) const { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; }
bool defaultValueAvailable(void) const { return _defaultValueAvailable; }
QString shortDescription(void) const { return _shortDescription; }
QString longDescription(void) const { return _longDescription;}
QString units(void) const { return _units; }
QVariant min(void) const { return _min; }
QVariant max(void) const { return _max; }
bool minIsDefaultForType(void) const { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; }
int decimalPlaces(void) const { return _decimalPlaces; }
// Property setters
void setName(const QString& name) { _name = name; }
......@@ -81,6 +82,7 @@ public:
void setUnits(const QString& units) { _units = units; }
void setMin(const QVariant& max);
void setMax(const QVariant& max);
void setDecimalPlaces(int decimalPlaces) { _decimalPlaces = decimalPlaces; }
/// Converts the specified value, validating against meta data
/// @param value Value to convert, can be string
......@@ -90,6 +92,8 @@ public:
/// @returns false: Convert failed, errorString set
bool convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString);
static const int defaultDecimalPlaces = 3;
private:
QVariant _minForType(void) const;
QVariant _maxForType(void) const;
......@@ -106,6 +110,7 @@ private:
QVariant _max;
bool _minIsDefaultForType;
bool _maxIsDefaultForType;
int _decimalPlaces;
};
#endif
......@@ -105,6 +105,10 @@ protected:
/// Base implementation adds generic meta data based on variant type. Derived class can override to provide
/// more details meta data.
virtual void _addMetaDataToFact(Fact* fact);
AutoPilotPlugin* _autopilot;
Vehicle* _vehicle;
MAVLinkProtocol* _mavlink;
private slots:
void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
......@@ -128,10 +132,6 @@ private:
void _saveToEEPROM(void);
void _checkInitialLoadComplete(void);
AutoPilotPlugin* _autopilot;
Vehicle* _vehicle;
MAVLinkProtocol* _mavlink;
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant;
......
......@@ -26,6 +26,7 @@
#include "APMFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack
#include "QGCMAVLink.h"
QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog")
......@@ -138,8 +139,9 @@ QString APMCustomMode::modeString() const
return mode;
}
APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) :
FirmwarePlugin(parent)
APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent)
: FirmwarePlugin(parent)
, _parameterLoader(NULL)
{
_textSeverityAdjustmentNeeded = false;
}
......@@ -384,3 +386,19 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
// APM stack wants the home position sent in the first position
return true;
}
ParameterLoader* APMFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle)
{
if (!_parameterLoader) {
_parameterLoader = new APMParameterLoader(autopilotPlugin, vehicle, this);
Q_CHECK_PTR(_parameterLoader);
// FIXME: Why do I need SIGNAL/SLOT to make this work
connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, &APMParameterLoader::parameterListProgress, autopilotPlugin, &APMAutoPilotPlugin::parameterListProgress);
_parameterLoader->loadParameterFactMetaData();
}
return _parameterLoader;
}
......@@ -29,6 +29,7 @@
#include "FirmwarePlugin.h"
#include "QGCLoggingCategory.h"
#include "APMParameterLoader.h"
Q_DECLARE_LOGGING_CATEGORY(APMFirmwarePluginLog)
......@@ -88,6 +89,7 @@ public:
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle);
protected:
/// All access to singleton is through stack specific implementation
......@@ -101,7 +103,7 @@ private:
APMFirmwareVersion _firmwareVersion;
bool _textSeverityAdjustmentNeeded;
QList<APMCustomMode> _supportedModes;
APMParameterLoader* _parameterLoader;
};
#endif
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "APMParameterLoader.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include <QFile>
#include <QFileInfo>
#include <QDir>
#include <QDebug>
QGC_LOGGING_CATEGORY(APMParameterLoaderLog, "APMParameterLoaderLog")
bool APMParameterLoader::_parameterMetaDataLoaded = false;
QMap<QString, FactMetaData*> APMParameterLoader::_mapParameterName2FactMetaData;
APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, vehicle, parent)
{
Q_ASSERT(vehicle);
}
/// Converts a string to a typed QVariant
/// @param string String to convert
/// @param type Type for Fact which dictates the QVariant type as well
/// @param convertOk Returned: true: conversion success, false: conversion failure
/// @return Returns the correctly type QVariant
QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk)
{
QVariant var(string);
int convertTo = QVariant::Int; // keep compiler warning happy
switch (type) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
convertTo = QVariant::UInt;
break;
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
convertTo = QVariant::Int;
break;
case FactMetaData::valueTypeFloat:
convertTo = QMetaType::Float;
break;
case FactMetaData::valueTypeDouble:
convertTo = QVariant::Double;
break;
}
*convertOk = var.convert(convertTo);
return var;
}
/// Load Parameter Fact meta data
///
/// The meta data comes from firmware parameters.xml file.
void APMParameterLoader::loadParameterFactMetaData(void)
{
if (_parameterMetaDataLoaded) {
return;
}
_parameterMetaDataLoaded = true;
// FIXME: NYI
// Static meta data should load all MAV_TYPEs from single meta data file in such a way that the loader
// has multiple sets of static meta data
}
void APMParameterLoader::clearStaticData(void)
{
foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) {
delete _mapParameterName2FactMetaData[parameterName];
}
_mapParameterName2FactMetaData.clear();
_parameterMetaDataLoaded = false;
}
/// Override from FactLoad which connects the meta data to the fact
void APMParameterLoader::_addMetaDataToFact(Fact* fact)
{
// FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data
// Use generic meta data
ParameterLoader::_addMetaDataToFact(fact);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef APMParameterLoader_H
#define APMParameterLoader_H
#include <QObject>
#include <QMap>
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include "ParameterLoader.h"
#include "FactSystem.h"
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(APMParameterLoaderLog)
/// Collection of Parameter Facts for PX4 AutoPilot
class APMParameterLoader : public ParameterLoader
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
static void loadParameterFactMetaData(void);
static void clearStaticData(void);
private:
enum {
XmlStateNone,
XmlStateFoundParameters,
XmlStateFoundVersion,
XmlStateFoundGroup,
XmlStateFoundParameter,
XmlStateDone
};
// Overrides from ParameterLoader
virtual void _addMetaDataToFact(Fact* fact);
// Class methods
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
static QMap<QString, FactMetaData*> _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
};
#endif
......@@ -105,6 +105,9 @@ public:
/// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual bool sendHomePositionToVehicle(void) = 0;
/// Returns the ParameterLoader
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) = 0;
protected:
FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { }
};
......
......@@ -25,13 +25,15 @@
/// @author Don Gagne <don@thegagnes.com>
#include "GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h" // FIXME: Hack
#include <QDebug>
IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin)
GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent) :
FirmwarePlugin(parent)
GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent)
: FirmwarePlugin(parent)
, _parameterLoader(NULL)
{
}
......@@ -118,3 +120,17 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
// This is the mavlink spec default.
return false;
}
ParameterLoader* GenericFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle)
{
if (!_parameterLoader) {
_parameterLoader = new GenericParameterLoader(autopilotPlugin, vehicle, this);
Q_CHECK_PTR(_parameterLoader);
// FIXME: Why do I need SIGNAL/SLOT to make this work
connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, &GenericParameterLoader::parameterListProgress, autopilotPlugin, &GenericAutoPilotPlugin::parameterListProgress);
}
return _parameterLoader;
}
......@@ -28,6 +28,7 @@
#define GenericFirmwarePlugin_H
#include "FirmwarePlugin.h"
#include "GenericParameterLoader.h"
class GenericFirmwarePlugin : public FirmwarePlugin
{
......@@ -47,10 +48,13 @@ public:
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle);
private:
/// All access to singleton is through AutoPilotPluginManager::instance
GenericFirmwarePlugin(QObject* parent = NULL);
GenericParameterLoader* _parameterLoader;
};
#endif
......@@ -21,15 +21,17 @@
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "GenericParameterLoader.h"
#include "GenericParameterFacts.h"
#include <QDebug>
GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
GenericParameterLoader::GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, vehicle, parent)
{
Q_ASSERT(vehicle);
}
/// Override from ParameterLoader which connects the meta data to the fact
void GenericParameterLoader::_addMetaDataToFact(Fact* fact)
{
// Use generic meta data
ParameterLoader::_addMetaDataToFact(fact);
}
......@@ -21,30 +21,28 @@
======================================================================*/
#ifndef GenericParameterFacts_h
#define GenericParameterFacts_h
#include <QObject>
#ifndef GenericParameterLoader_H
#define GenericParameterLoader_H
#include "ParameterLoader.h"
#include "UASInterface.h"
#include "FactSystem.h"
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
/// Collection of Parameter Facts for Generic AutoPilot
class GenericParameterFacts : public ParameterLoader
class GenericParameterLoader : public ParameterLoader
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
private:
// Overrides from ParameterLoader
virtual void _addMetaDataToFact(Fact* fact);
};
#endif
\ No newline at end of file
#endif
......@@ -25,6 +25,7 @@
/// @author Don Gagne <don@thegagnes.com>
#include "PX4FirmwarePlugin.h"
#include "AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h" // FIXME: Hack
#include <QDebug>
......@@ -85,8 +86,9 @@ static const struct Modes2Name rgModes2Name[] = {
};
PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent) :
FirmwarePlugin(parent)
PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent)
: FirmwarePlugin(parent)
, _parameterLoader(NULL)
{
}
......@@ -207,3 +209,19 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
// Subsequent sequence numbers must be adjusted.
return false;
}
ParameterLoader* PX4FirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle)
{
if (!_parameterLoader) {
_parameterLoader = new PX4ParameterLoader(autopilotPlugin, vehicle, this);
Q_CHECK_PTR(_parameterLoader);
// FIXME: Why do I need SIGNAL/SLOT to make this work
connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, &PX4ParameterLoader::parameterListProgress, autopilotPlugin, &PX4AutoPilotPlugin::parameterListProgress);
_parameterLoader->loadParameterFactMetaData();
}
return _parameterLoader;
}
......@@ -28,6 +28,7 @@
#define PX4FirmwarePlugin_H
#include "FirmwarePlugin.h"
#include "PX4ParameterLoader.h"
class PX4FirmwarePlugin : public FirmwarePlugin
{
......@@ -47,10 +48,13 @@ public:
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle);
private:
/// All access to singleton is through AutoPilotPluginManager::instance
PX4FirmwarePlugin(QObject* parent = NULL);
PX4ParameterLoader* _parameterLoader;
};
#endif
......@@ -299,6 +299,19 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
qCDebug(PX4ParameterLoaderLog) << "Unit:" << text;
metaData->setUnits(text);
} else if (elementName == "decimal") {
Q_ASSERT(metaData);
QString text = xml.readElementText();
qCDebug(PX4ParameterLoaderLog) << "Decimal:" << text;
bool convertOk;
QVariant varDecimals = QVariant(text).toUInt(&convertOk);
if (convertOk) {
metaData->setDecimalPlaces(varDecimals.toInt());
} else {
qCWarning(PX4ParameterLoaderLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number";
}
} else {
qDebug() << "Unknown element in XML: " << elementName;
}
......
......@@ -322,8 +322,6 @@ QGCView {
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
} else {
itemDragger.clearItem()
}
}
}
......
......@@ -20,15 +20,6 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
/**
* @file
* @brief MissionItem class
*
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include <QStringList>
#include <QDebug>
......@@ -115,10 +106,12 @@ MissionItem::MissionItem(QObject* parent,
FactMetaData* latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _latitudeFact);
latitudeMetaData->setUnits("deg");
latitudeMetaData->setDecimalPlaces(7);
FactMetaData* longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _longitudeFact);
longitudeMetaData->setUnits("deg");
longitudeMetaData->setDecimalPlaces(7);
FactMetaData* altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _altitudeFact);
altitudeMetaData->setUnits("meters");
......
......@@ -66,21 +66,23 @@ void MissionController::start(bool editMode)
connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
_setupMissionItems(true /* fromVehicle */, true /* force */);
_setupMissionItems(true /* loadFromVehicle */, true /* forceLoad */);
_setupActiveVehicle(multiVehicleMgr->activeVehicle(), true /* forceLoadFromVehicle */);
}
void MissionController::_newMissionItemsAvailableFromVehicle(void)
{
qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";
_setupMissionItems(true /* fromVehicle */, false /* force */);
_setupMissionItems(true /* loadFromVehicle */, false /* forceLoad */);
}
/// @param fromVehicle true: load items from vehicle
/// @param force true: disregard any flags which may prevent load
void MissionController::_setupMissionItems(bool fromVehicle, bool force)
/// @param loadFromVehicle true: load items from vehicle
/// @param forceLoad true: disregard any flags which may prevent load
void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad)
{
qCDebug(MissionControllerLog) << "_setupMissionItems fromVehicle:force:_editMode:_firstItemsFromVehicle" << fromVehicle << force << _editMode << _firstItemsFromVehicle;
qCDebug(MissionControllerLog) << "_setupMissionItems loadFromVehicle:forceLoad:_editMode:_firstItemsFromVehicle"
<< loadFromVehicle << forceLoad << _editMode << _firstItemsFromVehicle;
MissionManager* missionManager = NULL;
if (_activeVehicle) {
......@@ -89,8 +91,8 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force)
qCDebug(MissionControllerLog) << "running offline";
}
if (!force) {
if (_editMode && fromVehicle) {
if (!forceLoad) {
if (_editMode && loadFromVehicle) {
if (_firstItemsFromVehicle) {
if (missionManager) {
if (missionManager->inProgress()) {
......@@ -126,7 +128,7 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force)
_missionItems->deleteLater();
}
if (!missionManager || !fromVehicle || missionManager->inProgress()) {
if (!missionManager || !loadFromVehicle || missionManager->inProgress()) {
_canEdit = true;
_missionItems = new QmlObjectListModel(this);
qCDebug(MissionControllerLog) << "creating empty set";
......@@ -440,10 +442,22 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
_activeVehicle = NULL;
// When the active vehicle goes away we toss the editor items
_setupMissionItems(false /* fromVehicle */, true /* force */);
_setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */);
_activeVehicleHomePositionAvailableChanged(false);
}
_setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */);
}
void MissionController::_setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle)
{
qCDebug(MissionControllerLog) << "_setupActiveVehicle activeVehicle:forceLoadFromVehicle"
<< activeVehicle << forceLoadFromVehicle;
if (_activeVehicle) {
qCWarning(MissionControllerLog) << "_activeVehicle != NULL";
}
_activeVehicle = activeVehicle;
if (_activeVehicle) {
......@@ -455,7 +469,7 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
_firstItemsFromVehicle = true;
_setupMissionItems(true /* fromVehicle */, false /* force */);
_setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle);
_activeVehicleHomePositionChanged(_activeVehicle->homePosition());
_activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
......@@ -464,20 +478,15 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
MissionItem* homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
if (homePositionAvailable) {
homeItem->setCoordinate(_liveHomePosition);
}
homeItem->setHomePositionValid(homePositionAvailable);
_liveHomePositionAvailable = homePositionAvailable;
qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionAvailable);
emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}
void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
_liveHomePosition = homePosition;
qobject_cast<MissionItem*>(_missionItems->get(0))->setCoordinate(_liveHomePosition);
emit liveHomePositionChanged(_liveHomePosition);
}
......
......@@ -94,7 +94,8 @@ private:
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _autoSyncSend(void);
void _setupMissionItems(bool fromVehicle, bool force);
void _setupMissionItems(bool loadFromVehicle, bool forceLoad);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
private:
bool _editMode;
......
......@@ -45,6 +45,8 @@ Rectangle {
height: column.height + (ScreenTools.defaultFontPixelWidth * 2)
color: _qgcPal.window
signal modeChannelIndexSelected(int index)
QGCPalette { id: _qgcPal; colorGroupEnabled: enabled }
Item {
......@@ -63,7 +65,7 @@ Rectangle {
Rectangle {
width: modeLabel.width
height: modeLabel.contentHeight
color: modeSelected ? _qgcPal.buttonHighlight : _qgcPal.windowShade
color: modeSelected ? _qgcPal.buttonHighlight : _qgcPal.button
QGCLabel {
id: modeLabel
......@@ -82,7 +84,7 @@ Rectangle {
currentIndex: modeChannelIndex
enabled: modeChannelEnabled
onActivated: modeChannelIndex = index
onActivated: modeChannelIndexSelected(index)
}
QGCLabel {
......
......@@ -202,17 +202,32 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
bool emitHomePositionChanged = false;
bool emitHomePositionAvailableChanged = false;
mavlink_home_position_t homePos;
mavlink_msg_home_position_decode(&message, &homePos);
_homePosition.setLatitude(homePos.latitude / 10000000.0);
_homePosition.setLongitude(homePos.longitude / 10000000.0);
_homePosition.setAltitude(homePos.altitude / 1000.0);
QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
homePos.longitude / 10000000.0,
homePos.altitude / 1000.0);
if (newHomePosition != _homePosition) {
emitHomePositionChanged = true;
_homePosition = newHomePosition;
}
if (!_homePositionAvailable) {
emitHomePositionAvailableChanged = true;
}
_homePositionAvailable = true;
emit homePositionChanged(_homePosition);
emit homePositionAvailableChanged(true);
if (emitHomePositionChanged) {
emit homePositionChanged(_homePosition);
}
if (emitHomePositionAvailableChanged) {
emit homePositionAvailableChanged(true);
}
}
void Vehicle::_handleHeartbeat(mavlink_message_t& message)
......
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