Commit 6bc001e6 authored by Thomas Gubler's avatar Thomas Gubler

send rc to paramter map prototype

parent cf777949
Subproject commit 7d0aa0205ef8bd13bf855b21d3ebe054dc9109ef Subproject commit c0a0dff2b36a97614208559a23a9804ab9f2e636
...@@ -166,10 +166,10 @@ WindowsBuild { ...@@ -166,10 +166,10 @@ WindowsBuild {
} }
# #
# By default warnings as errors are turned off. Even so, in order for a pull request # By default warnings as errors are turned off. Even so, in order for a pull request
# to be accepted you must compile cleanly with warnings as errors turned on the default # to be accepted you must compile cleanly with warnings as errors turned on the default
# set of OS builds. See http://www.qgroundcontrol.org/dev/contribute for more details. # set of OS builds. See http://www.qgroundcontrol.org/dev/contribute for more details.
# You can use the WarningsAsErrorsOn CONFIG switch to turn warnings as errors on for your # You can use the WarningsAsErrorsOn CONFIG switch to turn warnings as errors on for your
# own builds. # own builds.
# #
...@@ -239,7 +239,7 @@ RESOURCES += qgroundcontrol.qrc ...@@ -239,7 +239,7 @@ RESOURCES += qgroundcontrol.qrc
TRANSLATIONS += \ TRANSLATIONS += \
es-MX.ts \ es-MX.ts \
en-US.ts en-US.ts
DEPENDPATH += \ DEPENDPATH += \
. \ . \
plugins plugins
...@@ -343,6 +343,7 @@ FORMS += \ ...@@ -343,6 +343,7 @@ FORMS += \
src/ui/px4_configuration/PX4FirmwareUpgrade.ui \ src/ui/px4_configuration/PX4FirmwareUpgrade.ui \
src/ui/QGCUASFileView.ui \ src/ui/QGCUASFileView.ui \
src/QGCQmlWidgetHolder.ui \ src/QGCQmlWidgetHolder.ui \
src/ui/QGCMapRCToParamDialog.ui
HEADERS += \ HEADERS += \
src/MG.h \ src/MG.h \
...@@ -495,6 +496,8 @@ HEADERS += \ ...@@ -495,6 +496,8 @@ HEADERS += \
src/QGCQuickWidget.h \ src/QGCQuickWidget.h \
src/QGCPalette.h \ src/QGCPalette.h \
src/QGCQmlWidgetHolder.h \ src/QGCQmlWidgetHolder.h \
src/ui/QGCParamTreeWidget.h \
src/ui/QGCMapRCToParamDialog.h
SOURCES += \ SOURCES += \
src/main.cc \ src/main.cc \
...@@ -636,13 +639,15 @@ SOURCES += \ ...@@ -636,13 +639,15 @@ SOURCES += \
src/QGCQuickWidget.cc \ src/QGCQuickWidget.cc \
src/QGCPalette.cc \ src/QGCPalette.cc \
src/QGCQmlWidgetHolder.cpp \ src/QGCQmlWidgetHolder.cpp \
src/ui/QGCParamTreeWidget.cpp \
src/ui/QGCMapRCToParamDialog.cpp
# #
# Unit Test specific configuration goes here # Unit Test specific configuration goes here
# #
# We have to special case Windows debug_and_release builds because you can't have files # We have to special case Windows debug_and_release builds because you can't have files
# which are only in the debug variant [QTBUG-40351]. So in this case we include unit tests # which are only in the debug variant [QTBUG-40351]. So in this case we include unit tests
# even in the release variant. If you want a Windows release build with no unit tests run # even in the release variant. If you want a Windows release build with no unit tests run
# qmake with CONFIG-=debug_and_release CONFIG+=release. # qmake with CONFIG-=debug_and_release CONFIG+=release.
# #
......
...@@ -2357,7 +2357,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2357,7 +2357,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
// Insert with correct type // Insert with correct type
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling. // TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
switch (rawValue.param_type) { switch (rawValue.param_type) {
case MAV_PARAM_TYPE_REAL32: case MAV_PARAM_TYPE_REAL32:
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
...@@ -2366,7 +2366,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2366,7 +2366,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
paramValue = QVariant(paramUnion.param_float); paramValue = QVariant(paramUnion.param_float);
} }
break; break;
case MAV_PARAM_TYPE_UINT8: case MAV_PARAM_TYPE_UINT8:
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
paramValue = QVariant(QChar((unsigned char)paramUnion.param_float)); paramValue = QVariant(QChar((unsigned char)paramUnion.param_float));
...@@ -2374,7 +2374,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2374,7 +2374,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
paramValue = QVariant(QChar((unsigned char)paramUnion.param_uint8)); paramValue = QVariant(QChar((unsigned char)paramUnion.param_uint8));
} }
break; break;
case MAV_PARAM_TYPE_INT8: case MAV_PARAM_TYPE_INT8:
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
paramValue = QVariant(QChar((char)paramUnion.param_float)); paramValue = QVariant(QChar((char)paramUnion.param_float));
...@@ -2382,7 +2382,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2382,7 +2382,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
paramValue = QVariant(QChar((char)paramUnion.param_int8)); paramValue = QVariant(QChar((char)paramUnion.param_int8));
} }
break; break;
case MAV_PARAM_TYPE_INT16: case MAV_PARAM_TYPE_INT16:
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
paramValue = QVariant((short)paramUnion.param_float); paramValue = QVariant((short)paramUnion.param_float);
...@@ -2390,7 +2390,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2390,7 +2390,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
paramValue = QVariant(paramUnion.param_int16); paramValue = QVariant(paramUnion.param_int16);
} }
break; break;
case MAV_PARAM_TYPE_UINT32: case MAV_PARAM_TYPE_UINT32:
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
paramValue = QVariant((unsigned int)paramUnion.param_float); paramValue = QVariant((unsigned int)paramUnion.param_float);
...@@ -2405,13 +2405,13 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, ...@@ -2405,13 +2405,13 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
paramValue = QVariant(paramUnion.param_int32); paramValue = QVariant(paramUnion.param_int32);
} }
break; break;
default: default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type; qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
} }
qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type; qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
parameters.value(compId)->insert(paramName, paramValue); parameters.value(compId)->insert(paramName, paramValue);
emit parameterChanged(uasId, compId, paramName, paramValue); emit parameterChanged(uasId, compId, paramName, paramValue);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, paramValue); emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, paramValue);
...@@ -3290,12 +3290,12 @@ void UAS::removeLink(QObject* object) ...@@ -3290,12 +3290,12 @@ void UAS::removeLink(QObject* object)
{ {
qCDebug(UASLog) << "removeLink:" << QString("%1").arg((ulong)object, 0, 16); qCDebug(UASLog) << "removeLink:" << QString("%1").arg((ulong)object, 0, 16);
qCDebug(UASLog) << "link count:" << links.count(); qCDebug(UASLog) << "link count:" << links.count();
// Do not dynamic cast or de-reference QObject, since object is either in destructor or may have already // Do not dynamic cast or de-reference QObject, since object is either in destructor or may have already
// been destroyed. // been destroyed.
LinkInterface* link = (LinkInterface*)object; LinkInterface* link = (LinkInterface*)object;
int index = links.indexOf(link); int index = links.indexOf(link);
Q_ASSERT(index != -1); Q_ASSERT(index != -1);
links.removeAt(index); links.removeAt(index);
...@@ -3467,3 +3467,41 @@ void UAS::stopLowBattAlarm() ...@@ -3467,3 +3467,41 @@ void UAS::stopLowBattAlarm()
lowBattAlarm = false; lowBattAlarm = false;
} }
} }
void UAS::sendMapRCToParam(QString param_id, float scale, float current_value, quint8 param_rc_channel_index)
{
qDebug() << "sendMapRCToParam" << param_id << "scale" << scale << "curval" << current_value << "param rc chan index" << param_rc_channel_index;
mavlink_message_t message;
mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&message,
this->uasId,
0,
param_id.toStdString().c_str(),
-1,
param_rc_channel_index,
current_value,
scale);
sendMessage(message);
qDebug() << "Mavlink message sent";
}
void UAS::unsetRCToParameterMap()
{
qDebug() << "unsetRCToParameterMap";
for (int i = 0; i < 3; i++) {
mavlink_message_t message;
mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&message,
this->uasId,
0,
"",
-2,
i,
0.0f,
0.0f);
sendMessage(message);
}
}
...@@ -883,6 +883,12 @@ public slots: ...@@ -883,6 +883,12 @@ public slots:
/** @brief Triggers the action associated with the given ID. */ /** @brief Triggers the action associated with the given ID. */
void triggerAction(int action); void triggerAction(int action);
/** @brief Send command to map a RC channel to a parameter */
void sendMapRCToParam(QString param_id, float scale, float current_value, quint8 param_rc_channel_index);
/** @brief Send command to disable all bindings/maps between RC and parameters */
void unsetRCToParameterMap();
signals: signals:
/** @brief The main/battery voltage has changed/was updated */ /** @brief The main/battery voltage has changed/was updated */
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
......
...@@ -199,32 +199,32 @@ public: ...@@ -199,32 +199,32 @@ public:
*/ */
static QColor getNextColor() { static QColor getNextColor() {
/* Create color map */ /* Create color map */
static QList<QColor> colors = QList<QColor>() static QList<QColor> colors = QList<QColor>()
<< QColor(231,72,28) << QColor(231,72,28)
<< QColor(104,64,240) << QColor(104,64,240)
<< QColor(203,254,121) << QColor(203,254,121)
<< QColor(161,252,116) << QColor(161,252,116)
<< QColor(232,33,47) << QColor(232,33,47)
<< QColor(116,251,110) << QColor(116,251,110)
<< QColor(234,38,107) << QColor(234,38,107)
<< QColor(104,250,138) << QColor(104,250,138)
<< QColor(235,43,165) << QColor(235,43,165)
<< QColor(98,248,176) << QColor(98,248,176)
<< QColor(236,48,221) << QColor(236,48,221)
<< QColor(92,247,217) << QColor(92,247,217)
<< QColor(200,54,238) << QColor(200,54,238)
<< QColor(87,231,246) << QColor(87,231,246)
<< QColor(151,59,239) << QColor(151,59,239)
<< QColor(81,183,244) << QColor(81,183,244)
<< QColor(75,133,243) << QColor(75,133,243)
<< QColor(242,255,128) << QColor(242,255,128)
<< QColor(230,126,23); << QColor(230,126,23);
static int nextColor = -1; static int nextColor = -1;
if(nextColor == 18){//if at the end of the list if(nextColor == 18){//if at the end of the list
nextColor = -1;//go back to the beginning nextColor = -1;//go back to the beginning
} }
nextColor++; nextColor++;
return colors[nextColor];//return the next color return colors[nextColor];//return the next color
} }
...@@ -391,6 +391,12 @@ public slots: ...@@ -391,6 +391,12 @@ public slots:
virtual void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x, virtual void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
float flow_comp_m_y, quint8 quality, float ground_distance) = 0; float flow_comp_m_y, quint8 quality, float ground_distance) = 0;
/** @brief Send command to map a RC channel to a parameter */
virtual void sendMapRCToParam(QString param_id, float scale, float current_value, quint8 param_rc_channel_index) = 0;
/** @brief Send command to disable all bindings/maps between RC and parameters */
virtual void unsetRCToParameterMap() = 0;
protected: protected:
QColor color; QColor color;
......
/*=====================================================================
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 Thomas Gubler <thomasgubler@gmail.com>
#include "QGCMapRCToParamDialog.h"
#include "ui_QGCMapRCToParamDialog.h"
#include <QDebug>
#include <QTimer>
#include <QEventLoop>
#include <QShowEvent>
#include <QPushButton>
QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id,
UASInterface *mav, QWidget *parent) :
QDialog(parent),
ui(new Ui::QGCMapRCToParamDialog),
param_id(param_id),
mav(mav)
{
ui->setupUi(this);
// only enable ok button when param was refreshed
QPushButton *okButton = ui->buttonBox->button(QDialogButtonBox::Ok);
okButton->setEnabled(false);
ui->paramIdLabel->setText(param_id);
// Refresh the param
ParamLoader *paramLoader = new ParamLoader(param_id, mav);
paramLoader->moveToThread(&paramLoadThread);
connect(&paramLoadThread, &QThread::finished, paramLoader, &QObject::deleteLater);
connect(this, &QGCMapRCToParamDialog::refreshParam, paramLoader, &ParamLoader::load);
connect(paramLoader, &ParamLoader::paramLoaded, this, &QGCMapRCToParamDialog::paramLoaded);
paramLoadThread.start();
emit refreshParam();
}
QGCMapRCToParamDialog::~QGCMapRCToParamDialog()
{
delete ui;
}
void QGCMapRCToParamDialog::accept() {
emit mapRCToParamDialogResult(param_id,
(float)ui->scaleDoubleSpinBox->value(),
(float)ui->value0DoubleSpinBox->value(),
(quint8)ui->rcParamChannelComboBox->currentIndex());
QDialog::accept();
}
void QGCMapRCToParamDialog::paramLoaded(bool success, float value, QString message)
{
paramLoadThread.quit();
if (success) {
ui->infoLabel->setText("Parameter value is up to date");
ui->value0DoubleSpinBox->setValue(value);
ui->value0DoubleSpinBox->setEnabled(true);
connect(this, &QGCMapRCToParamDialog::mapRCToParamDialogResult,
mav, &UASInterface::sendMapRCToParam);
QPushButton *okButton = ui->buttonBox->button(QDialogButtonBox::Ok);
okButton->setEnabled(true);
} else {
qDebug() << "Error while reading param" << param_id;
ui->infoLabel->setText("Error while refreshing param (" + message + ")");
}
}
void ParamLoader::load()
{
// refresh the parameter from onboard to make sure the current value is used
paramMgr->requestParameterUpdate(paramMgr->getDefaultComponentId(), param_id);
// wait until parameter update is received
QEventLoop loop;
QTimer timer;
connect(&timer, &QTimer::timeout, &loop, &QEventLoop::quit);
timer.start(10 * 1e3);
// overloaded signal:
connect(mav, static_cast<void (UASInterface::*)(
int, int, QString, QVariant)>(&UASInterface::parameterChanged),
this, &ParamLoader::handleParameterChanged);
connect(this, &ParamLoader::correctParameterChanged,
&loop, &QEventLoop::quit);
loop.exec();
if (!param_received == true) {
// timeout
emit paramLoaded(false, 0.0f, "Timeout");
return;
}
QVariant current_param_value;
bool got_param = paramMgr->getParameterValue(paramMgr->getDefaultComponentId(),
param_id, current_param_value);
QString message = got_param ? "" : "param manager Error";
emit paramLoaded(got_param, current_param_value.toFloat(), message);
}
void ParamLoader::handleParameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (uas == mav->getUASID() && parameterName == param_id) {
param_received = true;
emit correctParameterChanged();
}
}
/*=====================================================================
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
/// @brief Dialog to configure RC to paramter mapping
/// @author Thomas Gubler <thomasgubler@gmail.com>
#ifndef QGCMAPRCTOPARAMDIALOG_H
#define QGCMAPRCTOPARAMDIALOG_H
#include <QDialog>
#include <QThread>
#include "UASInterface.h"
namespace Ui {
class QGCMapRCToParamDialog;
}
class ParamLoader : public QObject
{
Q_OBJECT
public:
ParamLoader(QString param_id, UASInterface *mav, QObject * parent = 0):
QObject(parent),
mav(mav),
paramMgr(mav->getParamManager()),
param_id(param_id),
param_received(false)
{}
public slots:
void load();
void handleParameterChanged(int uas, int component, QString parameterName, QVariant value);
signals:
void paramLoaded(bool success, float value, QString message = "");
void correctParameterChanged();
protected:
UASInterface *mav;
QGCUASParamManagerInterface* paramMgr;
QString param_id;
bool param_received;
};
class QGCMapRCToParamDialog : public QDialog
{
Q_OBJECT
QThread paramLoadThread;
public:
explicit QGCMapRCToParamDialog(QString param_id,
UASInterface *mav, QWidget *parent = 0);
~QGCMapRCToParamDialog();
signals:
void mapRCToParamDialogResult(QString param_id, float scale, float current_value,
quint8 param_rc_channel_index);
void refreshParam();
public slots:
void accept();
void paramLoaded(bool success, float value, QString message);
protected:
// void showEvent(QShowEvent * event );
QString param_id;
UASInterface *mav;
private:
Ui::QGCMapRCToParamDialog *ui;
};
#endif // QGCMAPRCTOPARAMDIALOG_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMapRCToParamDialog</class>
<widget class="QDialog" name="QGCMapRCToParamDialog">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="windowTitle">
<string>Dialog</string>
</property>
<widget class="QDialogButtonBox" name="buttonBox">
<property name="geometry">
<rect>
<x>30</x>
<y>240</y>
<width>341</width>
<height>32</height>
</rect>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="standardButtons">
<set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
</property>
</widget>
<widget class="QWidget" name="formLayoutWidget">
<property name="geometry">
<rect>
<x>9</x>
<y>9</y>
<width>381</width>
<height>231</height>
</rect>
</property>
<layout class="QFormLayout" name="formLayout">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<item row="3" column="0">
<widget class="QLabel" name="paramIdInfoLabel">
<property name="text">
<string>Parameter</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLabel" name="paramIdLabel">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="scaleInfoLabel">
<property name="text">
<string>Scale</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QDoubleSpinBox" name="scaleDoubleSpinBox">
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="value0InfoLabel">
<property name="text">
<string>Initial Value</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QDoubleSpinBox" name="value0DoubleSpinBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="decimals">
<number>8</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="rcParamChannelInfoLabel">
<property name="text">
<string>RC-Parameter Channel (Knob No.)</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="rcParamChannelComboBox">
<property name="editable">
<bool>false</bool>
</property>
<property name="currentText">
<string>1</string>
</property>
<item>
<property name="text">
<string>1</string>
</property>
</item>
<item>
<property name="text">
<string>2</string>
</property>
</item>
<item>
<property name="text">
<string>3</string>
</property>
</item>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label1">
<property name="text">
<string>Bind</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label2">
<property name="text">
<string>to</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label3">
<property name="text">
<string>with</string>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="infoLabel">
<property name="text">
<string>Waiting for parameter refresh,,,</string>
</property>
</widget>
</item>
<item row="7" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
<resources/>
<connections>
<connection>
<sender>buttonBox</sender>
<signal>accepted()</signal>
<receiver>QGCMapRCToParamDialog</receiver>
<slot>accept()</slot>
<hints>
<hint type="sourcelabel">
<x>248</x>
<y>254</y>
</hint>
<hint type="destinationlabel">
<x>157</x>
<y>274</y>
</hint>
</hints>
</connection>
<connection>
<sender>buttonBox</sender>
<signal>rejected()</signal>
<receiver>QGCMapRCToParamDialog</receiver>
<slot>reject()</slot>
<hints>
<hint type="sourcelabel">
<x>316</x>
<y>260</y>
</hint>
<hint type="destinationlabel">
<x>286</x>
<y>274</y>
</hint>
</hints>
</connection>
</connections>
</ui>
/*=====================================================================
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 Thomas Gubler <thomasgubler@gmail.com>
#include "QGCParamTreeWidget.h"
#include <QMenu>
#include <QTreeWidgetItem>
#include <QDebug>
QGCParamTreeWidget::QGCParamTreeWidget(QWidget *parent) :
QTreeWidget(parent)
{
setContextMenuPolicy(Qt::CustomContextMenu);
QObject::connect(this, &QGCParamTreeWidget::customContextMenuRequested,
this, &QGCParamTreeWidget::showContextMenu);
qDebug() << "create QGCParamTreeWidget";
}
QGCParamTreeWidget::~QGCParamTreeWidget()
{
}
void QGCParamTreeWidget::showContextMenu(const QPoint &pos)
{
QMenu menu;
QTreeWidgetItem* item = itemAt(pos);
// Only show context menu for parameter items and not for group items
// (show for TEST_P but not for TEST)
// If a context menu is needed later for the groups then move this 'if'
// to below where the actions are created and filter out certain actions
// for the outer nodes
if (indexOfTopLevelItem(item) > -1 ||
indexOfTopLevelItem(item->parent()) > -1) {
return;
}
QString param_id = item->data(0, Qt::DisplayRole).toString();
QAction* act = new QAction(tr("Map Parameter to RC"), this);
act->setProperty("param_id", param_id);
connect(act, &QAction::triggered, this,
&QGCParamTreeWidget::contextMenuAction);
menu.addAction(act);
menu.exec(mapToGlobal(pos));
}
void QGCParamTreeWidget::contextMenuAction() {
QString param_id = qobject_cast<QAction*>(
sender())->property("param_id").toString();
emit mapRCToParamRequest(param_id);
}
/*=====================================================================
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
/// @brief A treeview with context menus for parameters
/// @author Thomas Gubler <thomasgubler@gmail.com>
#ifndef QGCPARAMTREEWIDGET_H
#define QGCPARAMTREEWIDGET_H
#include <QTreeWidget>
/// Implements individual context menus for the QTreeWidgetItems
class QGCParamTreeWidget : public QTreeWidget
{
Q_OBJECT
public:
QGCParamTreeWidget(QWidget *parent = 0);
~QGCParamTreeWidget();
signals:
void mapRCToParamRequest(QString param_id);
public slots:
void showContextMenu(const QPoint &pos);
void contextMenuAction();
};
#endif // QGCPARAMTREEWIDGET_H
...@@ -36,12 +36,15 @@ This file is part of the QGROUNDCONTROL project ...@@ -36,12 +36,15 @@ This file is part of the QGROUNDCONTROL project
#include <QPushButton> #include <QPushButton>
#include <QSettings> #include <QSettings>
#include <QTime> #include <QTime>
#include <QTimer>
#include <QEventLoop>
#include "MainWindow.h" #include "MainWindow.h"
#include "QGC.h" #include "QGC.h"
#include "QGCParamWidget.h" #include "QGCParamWidget.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASParameterCommsMgr.h" #include "UASParameterCommsMgr.h"
#include "QGCMapRCToParamDialog.h"
/** /**
* @param uas MAV to set the parameters on * @param uas MAV to set the parameters on
...@@ -51,7 +54,7 @@ QGCParamWidget::QGCParamWidget(QWidget *parent) : ...@@ -51,7 +54,7 @@ QGCParamWidget::QGCParamWidget(QWidget *parent) :
QGCBaseParamWidget(parent), QGCBaseParamWidget(parent),
componentItems(new QMap<int, QTreeWidgetItem*>()), componentItems(new QMap<int, QTreeWidgetItem*>()),
statusLabel(new QLabel(this)), statusLabel(new QLabel(this)),
tree(new QTreeWidget(this)), tree(new QGCParamTreeWidget(this)),
_fullParamListLoaded(false) _fullParamListLoaded(false)
{ {
...@@ -64,6 +67,8 @@ void QGCParamWidget::disconnectViewSignalsAndSlots() ...@@ -64,6 +67,8 @@ void QGCParamWidget::disconnectViewSignalsAndSlots()
{ {
disconnect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)), disconnect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)),
this, SLOT(parameterItemChanged(QTreeWidgetItem*,int))); this, SLOT(parameterItemChanged(QTreeWidgetItem*,int)));
disconnect(tree, &QGCParamTreeWidget::mapRCToParamRequest, this,
&QGCParamWidget::configureRCToParam);
} }
...@@ -72,6 +77,8 @@ void QGCParamWidget::connectViewSignalsAndSlots() ...@@ -72,6 +77,8 @@ void QGCParamWidget::connectViewSignalsAndSlots()
// Listen for edits to the tree UI // Listen for edits to the tree UI
connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)), connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)),
this, SLOT(parameterItemChanged(QTreeWidgetItem*,int))); this, SLOT(parameterItemChanged(QTreeWidgetItem*,int)));
connect(tree, &QGCParamTreeWidget::mapRCToParamRequest, this,
&QGCParamWidget::configureRCToParam);
} }
...@@ -119,6 +126,13 @@ void QGCParamWidget::addActionButtonsToLayout(QGridLayout* layout) ...@@ -119,6 +126,13 @@ void QGCParamWidget::addActionButtonsToLayout(QGridLayout* layout)
paramMgr, SLOT(copyPersistentParamsToVolatile())); paramMgr, SLOT(copyPersistentParamsToVolatile()));
layout->addWidget(readButton, 3, 2); layout->addWidget(readButton, 3, 2);
QPushButton* unsetRCToParamMapButton = new QPushButton(tr("Clear Rc to Param"));
unsetRCToParamMapButton->setToolTip(tr("Remove any bindings between RC channels and parameters."));
unsetRCToParamMapButton->setWhatsThis(tr("Remove any bindings between RC channels and parameters."));
connect(unsetRCToParamMapButton, &QPushButton::clicked,
mav, &UASInterface::unsetRCToParameterMap);
layout->addWidget(unsetRCToParamMapButton, 4, 1);
} }
void QGCParamWidget::layoutWidget() void QGCParamWidget::layoutWidget()
...@@ -241,9 +255,9 @@ void QGCParamWidget::handleOnboardParameterListUpToDate() ...@@ -241,9 +255,9 @@ void QGCParamWidget::handleOnboardParameterListUpToDate()
if (_fullParamListLoaded) { if (_fullParamListLoaded) {
return; return;
} }
_fullParamListLoaded = true; _fullParamListLoaded = true;
//turn off updates while we refresh the entire list //turn off updates while we refresh the entire list
tree->setUpdatesEnabled(false); tree->setUpdatesEnabled(false);
...@@ -355,7 +369,7 @@ void QGCParamWidget::insertParamAlphabetical(int indexLowerBound, int indexUpper ...@@ -355,7 +369,7 @@ void QGCParamWidget::insertParamAlphabetical(int indexLowerBound, int indexUpper
QTreeWidgetItem* QGCParamWidget::updateParameterDisplay(int compId, QString parameterName, QVariant value) QTreeWidgetItem* QGCParamWidget::updateParameterDisplay(int compId, QString parameterName, QVariant value)
{ {
//qDebug() << "QGCParamWidget::updateParameterDisplay" << parameterName; //qDebug() << "QGCParamWidget::updateParameterDisplay" << parameterName;
// Filter the parameters according to the filter list // Filter the parameters according to the filter list
if (_filterList.count() != 0) { if (_filterList.count() != 0) {
bool filterFound = false; bool filterFound = false;
...@@ -366,7 +380,7 @@ QTreeWidgetItem* QGCParamWidget::updateParameterDisplay(int compId, QString para ...@@ -366,7 +380,7 @@ QTreeWidgetItem* QGCParamWidget::updateParameterDisplay(int compId, QString para
} }
if (paramFilter == parameterName) { if (paramFilter == parameterName) {
filterFound = true; filterFound = true;
break; break;
} }
} }
if (!filterFound) { if (!filterFound) {
...@@ -509,7 +523,6 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* paramItem, int column ...@@ -509,7 +523,6 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* paramItem, int column
} }
} }
void QGCParamWidget::setParameterStatusMsg(const QString& msg) void QGCParamWidget::setParameterStatusMsg(const QString& msg)
{ {
statusLabel->setText(msg); statusLabel->setText(msg);
...@@ -544,3 +557,9 @@ void QGCParamWidget::handleParamStatusMsgUpdate(QString msg, int level) ...@@ -544,3 +557,9 @@ void QGCParamWidget::handleParamStatusMsgUpdate(QString msg, int level)
statusLabel->setPalette(pal); statusLabel->setPalette(pal);
statusLabel->setText(msg); statusLabel->setText(msg);
} }
void QGCParamWidget::configureRCToParam(QString param_id) {
QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(param_id,
mav, this);
d->exec();
}
...@@ -32,10 +32,10 @@ This file is part of the QGROUNDCONTROL project ...@@ -32,10 +32,10 @@ This file is part of the QGROUNDCONTROL project
#include <QWidget> #include <QWidget>
#include <QTreeWidget> #include <QTreeWidget>
#include <QTreeWidgetItem>
#include <QMap> #include <QMap>
#include <QLabel> #include <QLabel>
#include <QTimer> #include <QTimer>
#include "QGCParamTreeWidget.h"
#include "QGCBaseParamWidget.h" #include "QGCBaseParamWidget.h"
...@@ -52,7 +52,7 @@ class QGCParamWidget : public QGCBaseParamWidget ...@@ -52,7 +52,7 @@ class QGCParamWidget : public QGCBaseParamWidget
Q_OBJECT Q_OBJECT
public: public:
QGCParamWidget(QWidget *parent = 0); QGCParamWidget(QWidget *parent = 0);
/// @brief Sets the list of parameters which should be shown by this editor. Parameter names can be /// @brief Sets the list of parameters which should be shown by this editor. Parameter names can be
/// wildcarded at the end such as this: "RC*". Which will filter to all parameters which begin /// wildcarded at the end such as this: "RC*". Which will filter to all parameters which begin
/// with "RC". The wildcard (*) can only be at the end of the string. /// with "RC". The wildcard (*) can only be at the end of the string.
...@@ -75,10 +75,6 @@ protected: ...@@ -75,10 +75,6 @@ protected:
virtual void addActionButtonsToLayout(QGridLayout* layout); virtual void addActionButtonsToLayout(QGridLayout* layout);
signals:
public slots: public slots:
virtual void handleOnboardParamUpdate(int component,const QString& parameterName, QVariant value); virtual void handleOnboardParamUpdate(int component,const QString& parameterName, QVariant value);
virtual void handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending); virtual void handlePendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
...@@ -97,14 +93,18 @@ public slots: ...@@ -97,14 +93,18 @@ public slots:
/** @brief Update when user changes parameters */ /** @brief Update when user changes parameters */
void parameterItemChanged(QTreeWidgetItem* prev, int column); void parameterItemChanged(QTreeWidgetItem* prev, int column);
/** Promt configuration for param map config from user */
void configureRCToParam(QString param_id);
protected: protected:
QMap<int, QTreeWidgetItem*>* componentItems; ///< The tree of component items, stored by component ID QMap<int, QTreeWidgetItem*>* componentItems; ///< The tree of component items, stored by component ID
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups to organize component items QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups to organize component items
QLabel* statusLabel; ///< User-facing parameter status label QLabel* statusLabel; ///< User-facing parameter status label
QTreeWidget* tree; ///< The parameter tree QGCParamTreeWidget* tree; ///< The parameter tree
QStringList _filterList; QStringList _filterList;
private: private:
bool _fullParamListLoaded; bool _fullParamListLoaded;
}; };
......
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