Commit d2cc809e authored by Don Gagne's avatar Don Gagne

Merge pull request #1146 from DonLakeFlyer/Setup

Setup work
parents 1d5a457a e3acbf3b
......@@ -169,3 +169,8 @@ QUrl AirframeComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/AirframeComponentSummary.qml");
}
QString AirframeComponent::prerequisiteSetup(void) const
{
return QString();
}
......@@ -49,7 +49,8 @@ public:
virtual QString setupStateDescription(void) const;
virtual QWidget* setupWidget(void) const;
virtual QStringList paramFilterList(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QString prerequisiteSetup(void) const;
private:
const QString _name;
......
......@@ -104,12 +104,6 @@ void FlightModeConfig::_initUi(void) {
}
_updateAllSwitches();
// Finally if RC Calibration has not been performed disable the entire widget and inform user
if (_getChannelMapForParam(_modeSwitchParam) == 0) {
// FIXME: Do something more than disable
setEnabled(false);
}
}
void FlightModeConfig::_updateAllSwitches(void)
......
......@@ -27,6 +27,7 @@
#include "FlightModesComponent.h"
#include "FlightModeConfig.h"
#include "VehicleComponentSummaryItem.h"
#include "PX4AutoPilotPlugin.h"
/// @brief Parameters which signal a change in setupComplete state
static const char* triggerParams[] = { "RC_MAP_MODE_SW", NULL };
......@@ -121,3 +122,17 @@ QUrl FlightModesComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/FlightModesComponentSummary.qml");
}
QString FlightModesComponent::prerequisiteSetup(void) const
{
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
} else if (!plugin->radioComponent()->setupComplete()) {
return plugin->radioComponent()->name();
}
return QString();
}
......@@ -50,6 +50,7 @@ public:
virtual QWidget* setupWidget(void) const;
virtual QStringList paramFilterList(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QString prerequisiteSetup(void) const;
private:
const QString _name;
......
......@@ -22,11 +22,6 @@
======================================================================*/
#include "PX4AutoPilotPlugin.h"
#include "AirframeComponent.h"
#include "RadioComponent.h"
#include "SensorsComponent.h"
#include "FlightModesComponent.h"
#include "SafetyComponent.h"
#include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "QGCUASParamManagerInterface.h"
......@@ -36,7 +31,6 @@
/// @brief This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_PX4 type.
/// @author Don Gagne <don@thegagnes.com>
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
PX4_CUSTOM_MAIN_MODE_ALTCTL,
......@@ -69,7 +63,12 @@ union px4_custom_mode {
PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) :
AutoPilotPlugin(parent),
_uas(uas),
_parameterFacts(NULL)
_parameterFacts(NULL),
_airframeComponent(NULL),
_radioComponent(NULL),
_flightModesComponent(NULL),
_sensorsComponent(NULL),
_safetyComponent(NULL)
{
Q_ASSERT(uas);
......@@ -193,29 +192,27 @@ bool PX4AutoPilotPlugin::pluginIsReady(void) const
const QVariantList& PX4AutoPilotPlugin::components(void)
{
if (_components.count() == 0) {
VehicleComponent* component;
Q_ASSERT(_uas);
component = new AirframeComponent(_uas, this);
Q_CHECK_PTR(component);
_components.append(QVariant::fromValue(component));
_airframeComponent = new AirframeComponent(_uas, this);
Q_CHECK_PTR(_airframeComponent);
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
component = new RadioComponent(_uas, this);
Q_CHECK_PTR(component);
_components.append(QVariant::fromValue(component));
_radioComponent = new RadioComponent(_uas, this);
Q_CHECK_PTR(_radioComponent);
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
component = new FlightModesComponent(_uas, this);
Q_CHECK_PTR(component);
_components.append(QVariant::fromValue(component));
_flightModesComponent = new FlightModesComponent(_uas, this);
Q_CHECK_PTR(_flightModesComponent);
_components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent));
component = new SensorsComponent(_uas, this);
Q_CHECK_PTR(component);
_components.append(QVariant::fromValue(component));
_sensorsComponent = new SensorsComponent(_uas, this);
Q_CHECK_PTR(_sensorsComponent);
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
component = new SafetyComponent(_uas, this);
Q_CHECK_PTR(component);
_components.append(QVariant::fromValue(component));
_safetyComponent = new SafetyComponent(_uas, this);
Q_CHECK_PTR(_safetyComponent);
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
}
return _components;
......
......@@ -28,6 +28,11 @@
#include "AutoPilotPluginManager.h"
#include "UASInterface.h"
#include "PX4ParameterFacts.h"
#include "AirframeComponent.h"
#include "RadioComponent.h"
#include "FlightModesComponent.h"
#include "SensorsComponent.h"
#include "SafetyComponent.h"
#include <QImage>
......@@ -53,10 +58,22 @@ public:
static QString getShortModeText(uint8_t baseMode, uint32_t customMode);
static void clearStaticData(void);
// These methods should only be used by objects within the plugin
AirframeComponent* airframeComponent(void) { return _airframeComponent; }
RadioComponent* radioComponent(void) { return _radioComponent; }
FlightModesComponent* flightModesComponent(void) { return _flightModesComponent; }
SensorsComponent* sensorsComponent(void) { return _sensorsComponent; }
SafetyComponent* safetyComponent(void) { return _safetyComponent; }
private:
UASInterface* _uas;
PX4ParameterFacts* _parameterFacts;
QVariantList _components;
UASInterface* _uas;
PX4ParameterFacts* _parameterFacts;
QVariantList _components;
AirframeComponent* _airframeComponent;
RadioComponent* _radioComponent;
FlightModesComponent* _flightModesComponent;
SensorsComponent* _sensorsComponent;
SafetyComponent* _safetyComponent;
};
#endif
......@@ -44,7 +44,7 @@ void PX4Component::_parameterUpdated(int compId, QString paramName, QVariant val
while (*prgTriggers != NULL) {
if (paramName == *prgTriggers) {
emit setupCompleteChanged();
emit setupCompleteChanged(setupComplete());
return;
}
prgTriggers++;
......
......@@ -27,6 +27,7 @@
#include "RadioComponent.h"
#include "PX4RCCalibration.h"
#include "VehicleComponentSummaryItem.h"
#include "PX4AutoPilotPlugin.h"
/// @brief Parameters which signal a change in setupComplete state
static const char* triggerParams[] = { "RC_MAP_MODE_SW", NULL };
......@@ -105,3 +106,15 @@ QUrl RadioComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/RadioComponentSummary.qml");
}
QString RadioComponent::prerequisiteSetup(void) const
{
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
......@@ -51,6 +51,7 @@ public:
virtual QWidget* setupWidget(void) const;
virtual QStringList paramFilterList(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QString prerequisiteSetup(void) const;
private:
const QString _name;
......
......@@ -28,6 +28,7 @@
#include "PX4RCCalibration.h"
#include "VehicleComponentSummaryItem.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"
/// @brief Parameters which signal a change in setupComplete state
static const char* triggerParams[] = { NULL };
......@@ -104,3 +105,15 @@ QUrl SafetyComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/SafetyComponentSummary.qml");
}
QString SafetyComponent::prerequisiteSetup(void) const
{
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
......@@ -51,6 +51,7 @@ public:
virtual QWidget* setupWidget(void) const;
virtual QStringList paramFilterList(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QString prerequisiteSetup(void) const;
private:
const QString _name;
......
......@@ -27,6 +27,7 @@
#include "SensorsComponent.h"
#include "QGCPX4SensorCalibration.h"
#include "VehicleComponentSummaryItem.h"
#include "PX4AutoPilotPlugin.h"
// These two list must be kept in sync
......@@ -118,3 +119,15 @@ QUrl SensorsComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput("qrc:/qml/SensorsComponentSummary.qml");
}
QString SensorsComponent::prerequisiteSetup(void) const
{
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
......@@ -50,6 +50,7 @@ public:
virtual QWidget* setupWidget(void) const;
virtual QStringList paramFilterList(void) const;
virtual QUrl summaryQmlSource(void) const;
virtual QString prerequisiteSetup(void) const;
private:
const QString _name;
......
......@@ -33,6 +33,7 @@
#include "ParameterEditor.h"
#include "SetupWidgetHolder.h"
#include "MainWindow.h"
#include "QGCMessageBox.h"
#include <QQmlError>
#include <QQmlContext>
......@@ -117,6 +118,11 @@ void SetupView::_setConnectedView(void)
void SetupView::_firmwareButtonClicked(void)
{
if (_uasCurrent->isArmed()) {
QGCMessageBox::warning("Setup", "Firmware Update cannot be performed while vehicle is armed.");
return;
}
SetupWidgetHolder* dialog = new SetupWidgetHolder(MainWindow::instance());
dialog->setModal(true);
dialog->setWindowTitle("Firmware Upgrade");
......@@ -139,9 +145,20 @@ void SetupView::_parametersButtonClicked(void)
void SetupView::_setupButtonClicked(const QVariant& component)
{
if (_uasCurrent->isArmed()) {
QGCMessageBox::warning("Setup", "Setup cannot be performed while vehicle is armed.");
return;
}
VehicleComponent* vehicle = qobject_cast<VehicleComponent*>(component.value<QObject*>());
Q_ASSERT(vehicle);
QString setupPrereq = vehicle->prerequisiteSetup();
if (!setupPrereq.isEmpty()) {
QGCMessageBox::warning("Setup", QString("%1 setup must be completed prior to %2 setup.").arg(setupPrereq).arg(vehicle->name()));
return;
}
SetupWidgetHolder dialog(MainWindow::instance());
dialog.setModal(true);
dialog.setWindowTitle(vehicle->name());
......
......@@ -50,6 +50,7 @@ class VehicleComponent : public QObject
Q_PROPERTY(QString icon READ icon CONSTANT)
Q_PROPERTY(QWidget* setupWidget READ setupWidget STORED false)
Q_PROPERTY(QUrl summaryQmlSource READ summaryQmlSource CONSTANT);
Q_PROPERTY(QString prerequisiteSetup READ prerequisiteSetup)
public:
VehicleComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent = NULL);
......@@ -64,11 +65,12 @@ public:
virtual QWidget* setupWidget(void) const = 0;
virtual QStringList paramFilterList(void) const = 0;
virtual QUrl summaryQmlSource(void) const = 0;
virtual QString prerequisiteSetup(void) const = 0;
virtual void addSummaryQmlComponent(QQmlContext* context, QQuickItem* parent);
signals:
void setupCompleteChanged(void);
void setupCompleteChanged(bool setupComplete);
protected:
UASInterface* _uas;
......
......@@ -184,9 +184,8 @@ void UASParameterDataModel::handleParamUpdate(int compId, const QString &paramNa
}
}
emit parameterUpdated(compId,paramName,value);
setOnboardParam(compId,paramName,value);
emit parameterUpdated(compId,paramName,value);
}
bool UASParameterDataModel::getOnboardParamValue(int componentId, const QString& key, QVariant& value) const
......
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