Commit 995cf20f authored by Lorenz Meier's avatar Lorenz Meier

Config improvements, added firmware upload capability

parent 3726f315
......@@ -52,5 +52,5 @@ user_config.pri
thirdParty/qserialport-build-desktop/
thirdParty/qserialport/bin/
thirdParty/qserialport/lib/
apmplanner2.xcodeproj/
GeneratedFiles/
/qupgrade/
......@@ -142,6 +142,27 @@ INCLUDEPATH += \
include(src/apps/mavlinkgen/mavlinkgen.pri)
# Include QUpgrade tool
exists(qupgrade) {
SOURCES += qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.cpp \
qupgrade/src/apps/qupgrade/uploader.cpp \
qupgrade/src/apps/qupgrade/dialog_bare.cpp
HEADERS += qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.h \
qupgrade/src/apps/qupgrade/uploader.h \
qupgrade/src/apps/qupgrade/dialog_bare.h
FORMS += qupgrade/src/apps/qupgrade/dialog_bare.ui
linux*:CONFIG += qesp_linux_udev
include(qupgrade/libs/qextserialport/src/qextserialport.pri)
INCLUDEPATH += qupgrade/src/apps/qupgrade
DEFINES += "QUPGRADE_SUPPORT"
}
# Include QWT plotting library
include(libs/qwt/qwt.pri)
......@@ -153,12 +174,6 @@ INCLUDEPATH += .
# Include serial port library (QSerialPort)
include(libs/serialport/qserialport.pri)
## Serial port detection (ripped-off from qextserialport library)
#macx|macx-g++|macx-g++42::SOURCES += libs/qextserialport/qextserialenumerator_osx.cpp
#linux-g++::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
#linux-g++-64::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
#win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
# Input
FORMS += src/ui/MainWindow.ui \
src/ui/CommSettings.ui \
......
......@@ -157,18 +157,20 @@ void SerialLink::run()
int linkErrorCount = 0;
forever {
{
QMutexLocker locker(&this->m_stoppMutex);
if(m_stopp) {
m_stopp = false;
break; // exit the thread
}
if(m_stopp) {
m_stopp = false;
break; // exit the thread
}
if (m_reqReset) {
m_reqReset = false;
emit communicationUpdate(getName(),"Reset requested via DTR signal");
m_port->setDataTerminalReady(true);
msleep(250);
m_port->setDataTerminalReady(false);
if (m_reqReset) {
m_reqReset = false;
emit communicationUpdate(getName(),"Reset requested via DTR signal");
m_port->setDataTerminalReady(true);
msleep(250);
m_port->setDataTerminalReady(false);
}
}
if (isConnected() && (linkErrorCount > 100)) {
......
......@@ -48,7 +48,10 @@ void QGCUASParamManager::clearAllPendingParams()
paramDataModel.clearAllPendingParams();
}
QList<int> QGCUASParamManager::getComponentForParam(const QString& parameter) const
{
return paramDataModel.getComponentForOnboardParam(parameter);
}
bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const
......
......@@ -23,9 +23,32 @@ public:
/** @brief Get the known, confirmed value of a parameter */
virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const;
/**
* @brief Get a list of all component IDs using this parameter name
* @param parameter The string encoding the parameter name
* @return A list with all components using this parameter name. Can be empty.
*/
virtual QList<int> getComponentForParam(const QString& parameter) const;
/** @brief Provide tooltips / user-visible descriptions for parameters */
virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs);
/**
* @brief Count the pending parameters in the current transmission
* @return The number of pending parameters
*/
virtual int countPendingParams() {
return paramDataModel.countPendingParams();
}
/**
* @brief Count the number of onboard parameters
* @return The number of onboard parameters
*/
virtual int countOnboardParams() {
return paramDataModel.countOnboardParams();
}
/** @brief Get the UAS of this widget
* @return The MAV of this mgr. Unless the MAV object has been destroyed, this is never null.
*/
......
......@@ -192,6 +192,19 @@ bool UASParameterDataModel::getOnboardParamValue(int componentId, const QString&
return false;
}
QList<int> UASParameterDataModel::getComponentForOnboardParam(const QString& parameter) const
{
QList<int> components;
// Iterate through all components
foreach (int comp, onboardParameters.keys())
{
if (onboardParameters.value(comp)->contains(parameter))
components.append(comp);
}
return components;
}
void UASParameterDataModel::forgetAllOnboardParams()
{
onboardParameters.clear();
......
......@@ -34,7 +34,12 @@ public:
*/
virtual void addComponent(int compId);
/**
* @brief Return a list of all components for this parameter name
* @param parameter The parameter string to search for
* @return A list with all components, can be potentially empty
*/
virtual QList<int> getComponentForOnboardParam(const QString& parameter) const;
/** @brief Save the onboard parameter with a the type specified in the QVariant as fixed */
virtual void setOnboardParamWithType(int componentId, QString& key, QVariant& value);
......
......@@ -11,6 +11,7 @@
#include <QDir>
#include <QXmlStreamReader>
#include <QMessageBox>
#include <QLabel>
#include "QGCPX4VehicleConfig.h"
......@@ -21,12 +22,14 @@
#include "UASParameterCommsMgr.h"
#include "ui_QGCPX4VehicleConfig.h"
#include "px4_configuration/QGCPX4AirframeConfig.h"
#include <dialog_bare.h>
#define WIDGET_INDEX_RC 0
#define WIDGET_INDEX_SENSOR_CAL 1
#define WIDGET_INDEX_AIRFRAME_CONFIG 2
#define WIDGET_INDEX_GENERAL_CONFIG 3
#define WIDGET_INDEX_ADV_CONFIG 4
#define WIDGET_INDEX_FIRMWARE 0
#define WIDGET_INDEX_RC 1
#define WIDGET_INDEX_SENSOR_CAL 2
#define WIDGET_INDEX_AIRFRAME_CONFIG 3
#define WIDGET_INDEX_GENERAL_CONFIG 4
#define WIDGET_INDEX_ADV_CONFIG 5
#define MIN_PWM_VAL 800
#define MAX_PWM_VAL 2200
......@@ -48,6 +51,9 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
rc_mode(RC_MODE_NONE),
calibrationEnabled(false),
px4AirframeConfig(NULL),
#ifdef QUPGRADE_SUPPORT
firmwareDialog(NULL),
#endif
ui(new Ui::QGCPX4VehicleConfig)
{
doneLoadingConfig = false;
......@@ -71,6 +77,17 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
px4AirframeConfig = new QGCPX4AirframeConfig(this);
ui->airframeLayout->addWidget(px4AirframeConfig);
#ifdef QUPGRADE_SUPPORT
firmwareDialog = new DialogBare(this);
ui->firmwareLayout->addWidget(firmwareDialog);
#else
#error Please check out QUpgrade from http://github.com/LorenzMeier/qupgrade/ into the QGroundControl folder.
QLabel* label = new QLabel(this);
label->setText("THIS VERSION OF QGROUNDCONTROL WAS BUILT WITHOUT QUPGRADE. To enable firmware upload support, checkout QUpgrade WITHIN the QGroundControl folder");
ui->firmwareLayout->addWidget(label);
#endif
ui->rollWidget->setOrientation(Qt::Horizontal);
ui->rollWidget->setName("Roll");
ui->yawWidget->setOrientation(Qt::Horizontal);
......@@ -91,6 +108,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
connect(ui->generalMenuButton,SIGNAL(clicked()),this,SLOT(generalMenuButtonClicked()));
connect(ui->advancedMenuButton,SIGNAL(clicked()),this,SLOT(advancedMenuButtonClicked()));
connect(ui->airframeMenuButton, SIGNAL(clicked()), this, SLOT(airframeMenuButtonClicked()));
connect(ui->firmwareMenuButton, SIGNAL(clicked()), this, SLOT(firmwareButtonClicked()));
ui->rcCalibrationButton->setCheckable(true);
connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
......@@ -176,6 +194,11 @@ void QGCPX4VehicleConfig::airframeMenuButtonClicked()
ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_AIRFRAME_CONFIG);
}
void QGCPX4VehicleConfig::firmwareMenuButtonClicked()
{
ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_FIRMWARE);
}
void QGCPX4VehicleConfig::identifyChannelMapping(int aert_index)
{
if (chanCount == 0)
......@@ -1089,7 +1112,7 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val)
channelWanted = -1;
// Reject
// Confirm found channel
QMessageBox msgBox;
msgBox.setText(tr("%1 Channel found.").arg(channelNames[chanFound]));
msgBox.setInformativeText(tr("Found %1 to be on the raw RC channel %2").arg(channelNames[chanFound]).arg(chan + 1));
......
......@@ -13,6 +13,7 @@
#include "px4_configuration/QGCPX4AirframeConfig.h"
class UASParameterCommsMgr;
class DialogBare;
namespace Ui {
class QGCPX4VehicleConfig;
......@@ -40,6 +41,8 @@ public slots:
void generalMenuButtonClicked();
void advancedMenuButtonClicked();
void airframeMenuButtonClicked();
void firmwareMenuButtonClicked();
void identifyChannelMapping(int aert_index);
/** Set the MAV currently being calibrated */
......@@ -248,6 +251,7 @@ protected:
QMap<QString,QString> paramTooltips; ///< Tooltips for the ? button next to a parameter.
QGCPX4AirframeConfig* px4AirframeConfig;
DialogBare* firmwareDialog;
private:
Ui::QGCPX4VehicleConfig *ui;
......
......@@ -52,6 +52,14 @@
<property name="sizeConstraint">
<enum>QLayout::SetMinAndMaxSize</enum>
</property>
<item>
<widget class="QPushButton" name="firmwareMenuButton">
<property name="text">
<string>Firmware
Upgrade</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcMenuButton">
<property name="minimumSize">
......@@ -146,8 +154,19 @@ Config</string>
<item>
<widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex">
<number>1</number>
<number>0</number>
</property>
<widget class="QWidget" name="firmwareTab">
<layout class="QVBoxLayout" name="firmwareLayout">
<item>
<widget class="QLabel" name="label_5">
<property name="text">
<string>Firmware Upgrade</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="rcTab">
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
......
#include <QMessageBox>
#include "QGCPX4AirframeConfig.h"
#include "ui_QGCPX4AirframeConfig.h"
......@@ -7,6 +9,7 @@
QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) :
QWidget(parent),
mav(NULL),
selectedId(-1),
ui(new Ui::QGCPX4AirframeConfig)
{
ui->setupUi(this);
......@@ -62,23 +65,73 @@ void QGCPX4AirframeConfig::setActiveUAS(UASInterface* uas)
void QGCPX4AirframeConfig::setAirframeID(int id)
{
// If UAS is present, get param manager and set SYS_AUTOSTART ID
if (!mav)
return;
mav->getParamManager()->setParameter(0, "SYS_AUTOSTART", (qint32)id);
selectedId = id;
}
void QGCPX4AirframeConfig::applyAndReboot()
{
UAS* uas = qobject_cast<UAS*>(mav);
// Guard against the case of an edit where we didn't receive all params yet
if (selectedId < 0)
{
QMessageBox msgBox;
msgBox.setText(tr("No airframe selected"));
msgBox.setInformativeText(tr("Please select an airframe first."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
(void)msgBox.exec();
return;
}
if (!mav)
return;
if (mav->getParamManager()->countOnboardParams() == 0 &&
mav->getParamManager()->countPendingParams() == 0)
{
mav->getParamManager()->requestParameterListIfEmpty();
QGC::SLEEP::msleep(100);
}
// Guard against the case of an edit where we didn't receive all params yet
if (mav->getParamManager()->countPendingParams() > 0)
{
QMessageBox msgBox;
msgBox.setText(tr("Parameter sync with UAS not yet complete"));
msgBox.setInformativeText(tr("Please wait a few moments and retry"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
(void)msgBox.exec();
if (!uas)
return;
}
QList<int> components = mav->getParamManager()->getComponentForParam("SYS_AUTOSTART");
// Guard against multiple components responding - this will never show in practice
if (components.count() != 1) {
QMessageBox msgBox;
msgBox.setText(tr("Invalid system setup detected"));
msgBox.setInformativeText(tr("None or more than one component advertised to provide the main system configuration option. This is an invalid system setup - please check your autopilot."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
(void)msgBox.exec();
return;
}
qDebug() << "Setting comp" << components.first() << "SYS_AUTOSTART" << (qint32)selectedId;
mav->getParamManager()->setParameter(components.first(), "SYS_AUTOSTART", (qint32)selectedId);
// Send pending params
mav->getParamManager()->sendPendingParameters();
QGC::SLEEP::msleep(300);
// Store parameters
uas->executeCommand(MAV_CMD_PREFLIGHT_STORAGE, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
mav->getParamManager()->copyVolatileParamsToPersistent();
QGC::SLEEP::msleep(500);
// Reboot
uas->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
mav->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
}
void QGCPX4AirframeConfig::setAutoConfig(bool enabled)
......
......@@ -75,6 +75,7 @@ protected:
private:
UASInterface* mav;
int selectedId;
Ui::QGCPX4AirframeConfig *ui;
};
......
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