Browse Source

prelim extraction of read-only pending params widget

QGC4.4
tstellanova 12 years ago
parent
commit
624bb0a4ef
  1. 6
      qgroundcontrol.pro
  2. 8
      src/uas/QGCUASParamManager.cc
  3. 2
      src/uas/QGCUASParamManager.h
  4. 1
      src/ui/ParameterInterface.cc
  5. 8
      src/ui/QGCPX4VehicleConfig.cc
  6. 1
      src/ui/QGCPX4VehicleConfig.h
  7. 24
      src/ui/QGCPX4VehicleConfig.ui
  8. 19
      src/ui/QGCParamWidget.cc
  9. 4
      src/ui/QGCParamWidget.h
  10. 33
      src/ui/QGCPendingParamWidget.cc
  11. 26
      src/ui/QGCPendingParamWidget.h
  12. 23
      src/ui/designer/QGCComboBox.cc
  13. 4
      src/ui/designer/QGCComboBox.h
  14. 117
      src/ui/designer/QGCParamSlider.cc
  15. 4
      src/ui/designer/QGCParamSlider.h

6
qgroundcontrol.pro

@ -470,7 +470,8 @@ HEADERS += src/MG.h \ @@ -470,7 +470,8 @@ HEADERS += src/MG.h \
src/ui/configuration/ApmHighlighter.h \
src/ui/configuration/ApmFirmwareConfig.h \
src/uas/UASParameterDataModel.h \
src/uas/UASParameterCommsMgr.h
src/uas/UASParameterCommsMgr.h \
src/ui/QGCPendingParamWidget.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
@ -687,7 +688,8 @@ SOURCES += src/main.cc \ @@ -687,7 +688,8 @@ SOURCES += src/main.cc \
src/ui/configuration/ApmHighlighter.cc \
src/ui/configuration/ApmFirmwareConfig.cc \
src/uas/UASParameterDataModel.cc \
src/uas/UASParameterCommsMgr.cc
src/uas/UASParameterCommsMgr.cc \
src/ui/QGCPendingParamWidget.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc

8
src/uas/QGCUASParamManager.cc

@ -18,9 +18,6 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : @@ -18,9 +18,6 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) :
// Load default values and tooltips
loadParamMetaInfoCSV();
}
@ -75,6 +72,11 @@ void QGCUASParamManager::sendPendingParameters() @@ -75,6 +72,11 @@ void QGCUASParamManager::sendPendingParameters()
paramCommsMgr->sendPendingParameters();
}
void QGCUASParamManager::setPendingParam(int compId, QString& paramName, const QVariant& value)
{
paramDataModel->setPendingParam(compId,paramName,value);
}
void QGCUASParamManager::loadParamMetaInfoCSV()

2
src/uas/QGCUASParamManager.h

@ -49,6 +49,8 @@ public slots: @@ -49,6 +49,8 @@ public slots:
/** @brief Request list of parameters from MAV */
virtual void requestParameterList();
virtual void setPendingParam(int componentId, QString& key, const QVariant& value);
/** @brief Request a single parameter by name from the MAV */
virtual void requestParameterUpdate(int component, const QString& parameter);

1
src/ui/ParameterInterface.cc

@ -98,6 +98,7 @@ void ParameterInterface::addUAS(UASInterface* uas) @@ -98,6 +98,7 @@ void ParameterInterface::addUAS(UASInterface* uas)
}
QGCParamWidget* param = new QGCParamWidget(uas, this);
param->init();
QString ptrStr;
ptrStr.sprintf("QGCParamWidget %8p (parent %8p)", param,this);
qDebug() << "Created " << ptrStr << " for UAS id: " << uasId << " count: " << paramWidgets->count();

8
src/ui/QGCPX4VehicleConfig.cc

@ -15,6 +15,7 @@ @@ -15,6 +15,7 @@
#include "QGCPX4VehicleConfig.h"
#include "QGC.h"
#include "QGCPendingParamWidget.h"
#include "QGCToolWidget.h"
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
@ -82,7 +83,9 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : @@ -82,7 +83,9 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
//connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));
//TODO connect buttons here to save/clear actions?
ui->pendingCommitsWidget->init();
ui->pendingCommitsWidget->update();
//TODO the following methods are not yet implemented
@ -301,7 +304,6 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) @@ -301,7 +304,6 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary)
}
// Generate widgets for the Advanced tab.
left = true;
foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot))
{
if (file.toLower().endsWith(".qgw")) {
@ -1232,8 +1234,6 @@ void QGCPX4VehicleConfig::handleRcParameterChange(QString parameterName, QVarian @@ -1232,8 +1234,6 @@ void QGCPX4VehicleConfig::handleRcParameterChange(QString parameterName, QVarian
void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
Q_UNUSED(uas);
Q_UNUSED(component);
if (!doneLoadingConfig) {
//We do not want to attempt to generate any UI elements until loading of the config file is complete.
//We should re-request params later if needed, that is not implemented yet.

1
src/ui/QGCPX4VehicleConfig.h

@ -187,6 +187,7 @@ protected: @@ -187,6 +187,7 @@ protected:
QTimer updateTimer; ///< Controls update intervals
enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention
QList<QGCToolWidget*> toolWidgets; ///< Configurable widgets
QMap<QString,QGCToolWidget*> toolWidgetsByName; ///<
bool calibrationEnabled; ///< calibration mode on / off
QMap<QString,QGCToolWidget*> paramToWidgetMap; ///< Holds the current active MAV's parameter widgets.

24
src/ui/QGCPX4VehicleConfig.ui

@ -138,7 +138,7 @@ Config</string> @@ -138,7 +138,7 @@ Config</string>
<item>
<widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex">
<number>0</number>
<number>3</number>
</property>
<widget class="QWidget" name="rcTab">
<layout class="QVBoxLayout" name="verticalLayout_17">
@ -1035,8 +1035,8 @@ p, li { white-space: pre-wrap; } @@ -1035,8 +1035,8 @@ p, li { white-space: pre-wrap; }
<rect>
<x>0</x>
<y>0</y>
<width>16</width>
<height>16</height>
<width>597</width>
<height>569</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
@ -1168,7 +1168,17 @@ p, li { white-space: pre-wrap; } @@ -1168,7 +1168,17 @@ p, li { white-space: pre-wrap; }
<number>0</number>
</property>
<item>
<widget class="QTreeView" name="pendingCommitsTreeView"/>
<widget class="QGCPendingParamWidget" name="pendingCommitsWidget" native="true">
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="setButton">
@ -1259,6 +1269,12 @@ p, li { white-space: pre-wrap; } @@ -1259,6 +1269,12 @@ p, li { white-space: pre-wrap; }
<header>ui/designer/QGCRadioChannelDisplay.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>QGCPendingParamWidget</class>
<extends>QWidget</extends>
<header>/ui/QGCPendingParamWidget.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>

19
src/ui/QGCParamWidget.cc

@ -55,9 +55,19 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : @@ -55,9 +55,19 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
updatingParamNameLock("")
{
}
void QGCParamWidget::init()
{
layoutWidget();
connectSignalsAndSlots();
// Ensure we're receiving the list of params
requestAllParamsUpdate();
}
// Connect signals/slots
void QGCParamWidget::connectSignalsAndSlots()
{
// Listen for edits to the tree UI
connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)),
@ -77,15 +87,8 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : @@ -77,15 +87,8 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
// Listen to communications status messages so we can display them
connect(paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)),
this, SLOT(handleParamStatusMsgUpdate(QString , int )));
// Ensure we're receiving the list of params
requestAllParamsUpdate();
}
void QGCParamWidget::layoutWidget()
{
// Create tree widget

4
src/ui/QGCParamWidget.h

@ -48,10 +48,12 @@ class QGCParamWidget : public QGCUASParamManager @@ -48,10 +48,12 @@ class QGCParamWidget : public QGCUASParamManager
Q_OBJECT
public:
QGCParamWidget(UASInterface* uas, QWidget *parent = 0);
virtual void init(); ///< Two-stage construction: initialize the object
protected:
virtual void setParameterStatusMsg(const QString& msg);
virtual void layoutWidget();
virtual void layoutWidget();///< Layout the appearance of this widget
virtual void connectSignalsAndSlots();///< Connect signals/slots as needed
virtual QTreeWidgetItem* getParentWidgetItemForParam(int compId, const QString& paramName);
virtual QTreeWidgetItem* findChildWidgetItemForParam(QTreeWidgetItem* parentItem, const QString& paramName);

33
src/ui/QGCPendingParamWidget.cc

@ -0,0 +1,33 @@ @@ -0,0 +1,33 @@
#include "QGCPendingParamWidget.h"
#include "UASManager.h"
#include "UASParameterCommsMgr.h"
QGCPendingParamWidget::QGCPendingParamWidget(QObject *parent) :
QGCParamWidget(UASManager::instance()->getActiveUAS(),(QWidget*)parent)
{
}
void QGCPendingParamWidget::init()
{
//we override a lot of the super's init methods
layoutWidget();
connectSignalsAndSlots();
//don't request update params here...assume that everything we need is in the data model
}
void QGCPendingParamWidget::connectSignalsAndSlots()
{
// Listing for pending list update
connect(paramDataModel, SIGNAL(pendingParamUpdate(int , const QString&, QVariant , bool )),
this, SLOT(handlePendingParamUpdate(int , const QString& , QVariant, bool )));
// Listen to communications status messages so we can display them
connect(paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)),
this, SLOT(handleParamStatusMsgUpdate(QString , int )));
}

26
src/ui/QGCPendingParamWidget.h

@ -0,0 +1,26 @@ @@ -0,0 +1,26 @@
#ifndef QGCPENDINGPARAMWIDGET_H
#define QGCPENDINGPARAMWIDGET_H
#include "QGCParamWidget.h"
class QGCPendingParamWidget : public QGCParamWidget
{
Q_OBJECT
public:
explicit QGCPendingParamWidget(QObject* parent);
virtual void init(); ///< Two-stage construction: initialize the object
protected:
virtual void connectSignalsAndSlots();
signals:
public slots:
};
#endif // QGCPENDINGPARAMWIDGET_H

23
src/ui/designer/QGCComboBox.cc

@ -48,7 +48,7 @@ QGCComboBox::QGCComboBox(QWidget *parent) : @@ -48,7 +48,7 @@ QGCComboBox::QGCComboBox(QWidget *parent) :
connect(ui->editRemoveItemButton,SIGNAL(clicked()),this,SLOT(delButtonClicked()));
// Sending actions
connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(sendParameter()));
connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(setParamPending()));
connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int)));
connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int)));
//connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int)));
@ -233,24 +233,13 @@ void QGCComboBox::endEditMode() @@ -233,24 +233,13 @@ void QGCComboBox::endEditMode()
emit editingFinished();
}
void QGCComboBox::sendParameter()
void QGCComboBox::setParamPending()
{
if (uas)
{
// Set value, param manager handles retransmission
if (uas->getParamManager())
{
qDebug() << "Sending param:" << parameterName << "to component" << component << "with a value of" << parameterValue;
uas->getParamManager()->setParameter(component, parameterName, parameterValue);
}
else
{
qDebug() << "UAS HAS NO PARAM MANAGER, DOING NOTHING";
}
if (uas) {
uas->getParamManager()->setPendingParam(component, parameterName, parameterValue);
}
else
{
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
else {
qWarning() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
}

4
src/ui/designer/QGCComboBox.h

@ -23,8 +23,8 @@ public: @@ -23,8 +23,8 @@ public:
public slots:
void startEditMode();
void endEditMode();
/** @brief Send the parameter to the MAV */
void sendParameter();
/** @brief Queue parameter for sending to the MAV (add to pending list)*/
void setParamPending();
/** @brief Update the UI with the new parameter value */
void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, const QVariant value);
void writeSettings(QSettings& settings);

117
src/ui/designer/QGCParamSlider.cc

@ -47,20 +47,31 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) : @@ -47,20 +47,31 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
// Sending actions
connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(sendParameter()));
connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int)));
connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int)));
connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int)));
connect(ui->doubleValueSpinBox, SIGNAL(valueChanged(double)), this, SLOT(setParamValue(double)));
connect(ui->intValueSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setParamValue(int)));
connect(ui->editNameLabel, SIGNAL(textChanged(QString)), ui->nameLabel, SLOT(setText(QString)));
connect(ui->writeButton, SIGNAL(clicked()),
this, SLOT(setParamPending()));
connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)),
this, SLOT(selectComponent(int)));
connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)),
this, SLOT(selectParameter(int)));
connect(ui->valueSlider, SIGNAL(valueChanged(int)),
this, SLOT(setSliderValue(int)));
connect(ui->doubleValueSpinBox, SIGNAL(valueChanged(double)),
this, SLOT(setParamValue(double)));
connect(ui->intValueSpinBox, SIGNAL(valueChanged(int)),
this, SLOT(setParamValue(int)));
connect(ui->editNameLabel, SIGNAL(textChanged(QString)),
ui->nameLabel, SLOT(setText(QString)));
connect(ui->readButton, SIGNAL(clicked()), this, SLOT(requestParameter()));
connect(ui->editRefreshParamsButton, SIGNAL(clicked()), this, SLOT(refreshParamList()));
connect(ui->editInfoCheckBox, SIGNAL(clicked(bool)), this, SLOT(showInfo(bool)));
connect(ui->editRefreshParamsButton, SIGNAL(clicked()),
this, SLOT(refreshParamList()));
connect(ui->editInfoCheckBox, SIGNAL(clicked(bool)),
this, SLOT(showInfo(bool)));
// connect to self
connect(ui->infoLabel, SIGNAL(released()), this, SLOT(showTooltip()));
connect(ui->infoLabel, SIGNAL(released()),
this, SLOT(showTooltip()));
// Set the current UAS if present
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
this, SLOT(setActiveUAS(UASInterface*)));
}
QGCParamSlider::~QGCParamSlider()
@ -83,8 +94,7 @@ void QGCParamSlider::refreshParamList() @@ -83,8 +94,7 @@ void QGCParamSlider::refreshParamList()
{
ui->editSelectParamComboBox->setEnabled(true);
ui->editSelectComponentComboBox->setEnabled(true);
if (uas)
{
if (uas) {
uas->getParamManager()->requestParameterList();
ui->editStatusLabel->setText(tr("Parameter list updating.."));
}
@ -122,9 +132,8 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas) @@ -122,9 +132,8 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas)
void QGCParamSlider::requestParameter()
{
if (!parameterName.isEmpty() && uas)
{
uas->getParamManager()->requestParameterUpdate(this->component, this->parameterName);
if (uas && !parameterName.isEmpty()) {
uas->getParamManager()->requestParameterUpdate(component, parameterName);
}
}
@ -268,23 +277,13 @@ void QGCParamSlider::endEditMode() @@ -268,23 +277,13 @@ void QGCParamSlider::endEditMode()
emit editingFinished();
}
void QGCParamSlider::sendParameter()
{
if (uas)
{
// Set value, param manager handles retransmission
if (uas->getParamManager())
{
uas->getParamManager()->setParameter(component, parameterName, parameterValue);
}
else
void QGCParamSlider::setParamPending()
{
qDebug() << "UAS HAS NO PARAM MANAGER, DOING NOTHING";
}
if (uas) {
uas->getParamManager()->setPendingParam(component, parameterName, parameterValue);
}
else
{
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
else {
qWarning() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
}
@ -329,55 +328,48 @@ void QGCParamSlider::setSliderValue(int sliderValue) @@ -329,55 +328,48 @@ void QGCParamSlider::setSliderValue(int sliderValue)
* @brief parameterName Key/name of the parameter
* @brief value Value of the parameter
*/
void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, QVariant value)
void QGCParamSlider::setParameterValue(int uasId, int compId, int paramCount, int paramIndex, QString paramName, QVariant value)
{
Q_UNUSED(paramCount);
if (ui->nameLabel->text() == "Name")
{
ui->nameLabel->setText(parameterName);
if (uasId != this->uas->getUASID()) {
return;
}
if (ui->nameLabel->text() == "Name") {
ui->nameLabel->setText(paramName);
}
// Check if this component and parameter are part of the list
bool found = false;
for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i)
{
if (component == ui->editSelectComponentComboBox->itemData(i).toInt())
{
for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i) {
if (compId == ui->editSelectComponentComboBox->itemData(i).toInt()) {
found = true;
}
}
if (!found)
{
ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(component), component);
if (!found) {
ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(compId), compId);
}
// Parameter checking
found = false;
for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i)
{
if (parameterName == ui->editSelectParamComboBox->itemText(i))
{
for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i) {
if (paramName == ui->editSelectParamComboBox->itemText(i)) {
found = true;
}
}
if (!found)
{
ui->editSelectParamComboBox->addItem(parameterName, paramIndex);
if (!found) {
ui->editSelectParamComboBox->addItem(paramName, paramIndex);
}
if (visibleParam != "")
{
if (parameterName == visibleParam)
{
if (visibleVal == value.toInt())
{
this->uas->requestParameter(this->component,this->parameterName);
if (visibleParam != "") {
if (paramName == visibleParam) {
if (visibleVal == value.toInt()) {
uas->getParamManager()->requestParameterUpdate(compId,paramName);
visibleEnabled = true;
this->show();
}
else
{
else {
//Disable the component here.
ui->valueSlider->setEnabled(false);
ui->intValueSpinBox->setEnabled(false);
@ -388,10 +380,8 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i @@ -388,10 +380,8 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i
}
}
Q_UNUSED(uas);
if (component == this->component && parameterName == this->parameterName)
{
if (!visibleEnabled)
{
if (compId == this->component && paramName == this->parameterName) {
if (!visibleEnabled) {
return;
}
parameterValue = value;
@ -460,8 +450,7 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i @@ -460,8 +450,7 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i
parameterMin = ui->editMinSpinBox->value();
}
if (paramIndex == paramCount - 1)
{
if (paramIndex == paramCount - 1) {
ui->editStatusLabel->setText(tr("Complete parameter list received."));
}
}

4
src/ui/designer/QGCParamSlider.h

@ -23,8 +23,8 @@ public: @@ -23,8 +23,8 @@ public:
public slots:
void startEditMode();
void endEditMode();
/** @brief Send the parameter to the MAV */
void sendParameter();
/** @brief Queue parameter for sending to the MAV (add to pending list)*/
void setParamPending();
/** @brief Set the slider value as parameter value */
void setSliderValue(int sliderValue);
/** @brief Update the UI with the new parameter value */

Loading…
Cancel
Save