Commit 107d7167 authored by Lorenz Meier's avatar Lorenz Meier

Fixed race issues in config upload, tested to be reliable now - board startup...

Fixed race issues in config upload, tested to be reliable now - board startup scripts now need the other half of testing
parent 40202972
......@@ -249,7 +249,12 @@ QLabel#noUas {
}
QMessageBox QLabel {
font-size: 12pt;
font-size: 14pt;
}
QMessageBox {
min-width: 400px;
min-height: 300px;
}
QLabel#calibrationExplanationLabel {
......
......@@ -250,9 +250,9 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
if (decodeState == 0 && !decodedFirstPacket)
{
nonmavlinkCount++;
if (nonmavlinkCount > 500 && !warnedUserNonMavlink)
if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
{
//500 bytes with no mavlink message. Are we connected to a mavlink capable device?
//2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
if (!checkedUserNonMavlink)
{
link->requestReset();
......
......@@ -183,7 +183,7 @@ void SerialLink::run()
if (m_transmitBuffer.count() > 0) {
QMutexLocker writeLocker(&m_writeMutex);
int numWritten = m_port->write(m_transmitBuffer);
bool txSuccess = m_port->waitForBytesWritten(1);
bool txSuccess = m_port->waitForBytesWritten(5);
if (!txSuccess || (numWritten != m_transmitBuffer.count())) {
linkErrorCount++;
qDebug() << "TX Error! wrote" << numWritten << ", asked for " << m_transmitBuffer.count() << "bytes";
......
......@@ -1182,12 +1182,11 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float fval)
// Raw value
float mappedVal = rcMappedValue[rcToFunctionMapping[chan]];
bool isMapped = (((float)UINT16_MAX) != mappedVal);
float deltaRaw = fabsf(fval - rcValue[chan]);
float delta = fabsf(fval - mappedVal);
if (!configEnabled && !calibrationEnabled &&
(!isMapped ||
(delta < 12.0f && rcValue[chan] > 800 && rcValue[chan] < 2200) )
) {
(deltaRaw < 12.0f && delta < 12.0f && rcValue[chan] > 800 && rcValue[chan] < 2200))
{
//ignore tiny jitter values
return;
}
......
......@@ -798,40 +798,6 @@
</font>
</property>
<layout class="QVBoxLayout" name="verticalLayout_11">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QComboBox" name="multiRotorComboBox"/>
</item>
<item>
<widget class="QPushButton" name="loadMultiRotorDefaultsButton">
<property name="font">
<font>
<pointsize>13</pointsize>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>Load Platform Defaults</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
......@@ -853,8 +819,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>98</width>
<height>28</height>
<width>492</width>
<height>828</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_4">
......@@ -890,8 +856,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>98</width>
<height>28</height>
<width>491</width>
<height>828</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_5">
......@@ -914,33 +880,6 @@
</widget>
<widget class="QWidget" name="advancedTab">
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QComboBox" name="platformSelectorComboBox"/>
</item>
<item>
<widget class="QPushButton" name="loadPlatformDefaultsButton">
<property name="text">
<string>Load Platform Defaults</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
......
#include <QMessageBox>
#include <QProgressDialog>
#include <QDebug>
#include <QTimer>
#include "QGCPX4AirframeConfig.h"
#include "ui_QGCPX4AirframeConfig.h"
......@@ -7,10 +9,14 @@
#include "UASManager.h"
#include "LinkManager.h"
#include "UAS.h"
#include "QGC.h"
QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) :
QWidget(parent),
mav(NULL),
progress(NULL),
pendingParams(0),
configState(CONFIG_STATE_ABORT),
selectedId(-1),
ui(new Ui::QGCPX4AirframeConfig)
{
......@@ -75,6 +81,7 @@ void QGCPX4AirframeConfig::parameterChanged(int uas, int component, QString para
setAirframeID(index);
ui->statusLabel->setText(tr("Onboard start script ID: #%1").arg(index));
} else {
uncheckAll();
ui->statusLabel->setText(tr("System not configured for autostart."));
}
}
......@@ -171,12 +178,14 @@ void QGCPX4AirframeConfig::applyAndReboot()
if (paramMgr->countOnboardParams() == 0 &&
paramMgr->countPendingParams() == 0)
{
paramMgr->requestParameterListIfEmpty();
QGC::SLEEP::msleep(100);
paramMgr->requestParameterList();
QGC::SLEEP::msleep(300);
}
QList<int> components = paramMgr->getComponentForParam("SYS_AUTOSTART");
// Guard against the case of an edit where we didn't receive all params yet
if (paramMgr->countPendingParams() > 0)
if (paramMgr->countPendingParams() > 0 || components.count() == 0)
{
QMessageBox msgBox;
msgBox.setText(tr("Parameter sync with UAS not yet complete"));
......@@ -188,8 +197,6 @@ void QGCPX4AirframeConfig::applyAndReboot()
return;
}
QList<int> components = paramMgr->getComponentForParam("SYS_AUTOSTART");
// Guard against multiple components responding - this will never show in practice
if (components.count() != 1) {
QMessageBox msgBox;
......@@ -202,32 +209,137 @@ void QGCPX4AirframeConfig::applyAndReboot()
return;
}
qDebug() << "Setting comp" << components.first() << "SYS_AUTOSTART" << (qint32)selectedId;
paramMgr->setPendingParam(components.first(),"SYS_AUTOSTART", (qint32)selectedId);
//need to set autoconfig in order for PX4 to pick up the selected airframe params
if (ui->defaultGainsCheckBox->checkState() == Qt::Checked)
setAutoConfig(true);
// Send pending params and then write them to persistent storage when done
paramMgr->sendPendingParameters(true);
// Reboot
//TODO right now this relies upon the above send & persist finishing before the reboot command is received...
QMessageBox msgBox(this);
msgBox.setText(tr("Storing Parameters and Rebooting Autopilot"));
msgBox.setInformativeText(tr("Please wait a few seconds for the reboot to complete."));
msgBox.setStandardButtons(QMessageBox::NoButton);
msgBox.setModal(false);
msgBox.show();
QGC::SLEEP::sleep(2);
mav->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
QGC::SLEEP::msleep(200);
LinkManager::instance()->disconnectAll();
QGC::SLEEP::sleep(8);
LinkManager::instance()->connectAll();
msgBox.close();
// This is really evil: 'fake' a thread by
// periodic work queue calls and clock
// through a small state machine
// ugh.. if we just had time to do this properly.
// To the reader who can't program and wants to whine:
// this is not beautiful, but technically completely
// sound. If you want to fix it, you'd be welcome
// to rebase the link, param manager and UI classes
// on a proper threading framework - which I'd love to do
// if I just had more time..
configState = CONFIG_STATE_SEND;
QTimer::singleShot(200, this, SLOT(checkConfigState()));
}
void QGCPX4AirframeConfig::checkConfigState()
{
if (configState == CONFIG_STATE_SEND)
{
QList<int> components = paramMgr->getComponentForParam("SYS_AUTOSTART");
qDebug() << "Setting comp" << components.first() << "SYS_AUTOSTART" << (qint32)selectedId;
paramMgr->setPendingParam(components.first(),"SYS_AUTOSTART", (qint32)selectedId);
//need to set autoconfig in order for PX4 to pick up the selected airframe params
if (ui->defaultGainsCheckBox->checkState() == Qt::Checked)
setAutoConfig(true);
// Send pending params and then write them to persistent storage when done
paramMgr->sendPendingParameters(true);
configState = CONFIG_STATE_WAIT_PENDING;
pendingParams = 0;
QTimer::singleShot(2000, this, SLOT(checkConfigState()));
return;
}
if (configState == CONFIG_STATE_WAIT_PENDING) {
// Guard against the case of an edit where we didn't receive all params yet
if (paramMgr->countPendingParams() > 0)
{
if (pendingParams == 0) {
pendingParams = paramMgr->countPendingParams();
if (progress)
delete progress;
progress = new QProgressDialog("Writing parameters", "Abort Send", 0, pendingParams, this);
progress->setWindowModality(Qt::WindowModal);
progress->setMinimumDuration(2000);
}
qDebug() << "PENDING" << paramMgr->countPendingParams() << "PROGRESS" << pendingParams - paramMgr->countPendingParams();
progress->setValue(pendingParams - paramMgr->countPendingParams());
if (progress->wasCanceled()) {
configState = CONFIG_STATE_ABORT;
pendingParams = 0;
return;
}
} else {
pendingParams = 0;
configState = CONFIG_STATE_REBOOT;
}
qDebug() << "PENDING PARAMS WAIT PENDING: " << paramMgr->countPendingParams();
QTimer::singleShot(1000, this, SLOT(checkConfigState()));
return;
}
if (configState == CONFIG_STATE_REBOOT) {
// Reboot
//TODO right now this relies upon the above send & persist finishing before the reboot command is received...
unsigned pendingMax = 20;
qDebug() << "PENDING PARAMS REBOOT BEFORE" << pendingParams;
if (pendingParams == 0) {
pendingParams = 1;
if (progress)
delete progress;
progress = new QProgressDialog("Waiting for autopilot reboot", "Abort", 0, pendingMax, this);
progress->setWindowModality(Qt::WindowModal);
qDebug() << "Waiting for reboot, pending" << pendingParams;
}
if (pendingParams == 3) {
qDebug() << "REQUESTING REBOOT";
mav->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);
}
if (pendingParams == 4) {
qDebug() << "DISCONNECT AIRFRAME";
LinkManager::instance()->disconnectAll();
}
if (pendingParams == 14) {
qDebug() << "CONNECT AIRFRAME";
LinkManager::instance()->connectAll();
}
if (pendingParams == 15) {
qDebug() << "DISCONNECT AIRFRAME";
LinkManager::instance()->disconnectAll();
}
if (pendingParams == 16) {
qDebug() << "CONNECT AIRFRAME";
LinkManager::instance()->connectAll();
}
if (pendingParams < pendingMax) {
progress->setValue(pendingParams);
QTimer::singleShot(1000, this, SLOT(checkConfigState()));
} else {
paramMgr->requestParameterList();
progress->setValue(pendingMax);
configState = CONFIG_STATE_ABORT;
pendingParams = 0;
return;
}
qDebug() << "PENDING PARAMS REBOOT AFTER:" << pendingParams;
pendingParams++;
return;
}
}
void QGCPX4AirframeConfig::setAutoConfig(bool enabled)
......
......@@ -4,6 +4,8 @@
#include <QWidget>
#include <UASInterface.h>
class QProgressDialog;
namespace Ui {
class QGCPX4AirframeConfig;
}
......@@ -67,6 +69,9 @@ public slots:
*/
void applyAndReboot();
protected slots:
void checkConfigState();
protected:
/**
......@@ -83,9 +88,19 @@ protected:
void uncheckAll();
enum CONFIG_STATE {
CONFIG_STATE_ABORT = 0,
CONFIG_STATE_SEND,
CONFIG_STATE_WAIT_PENDING,
CONFIG_STATE_REBOOT
};
private:
UASInterface* mav;
QGCUASParamManager *paramMgr;
QProgressDialog* progress;
unsigned pendingParams;
enum CONFIG_STATE configState;
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