Commit 2d0bf535 authored by pixhawk's avatar pixhawk

Fixing the parameter view

parent 85be7c6a
......@@ -3,50 +3,50 @@ INCLUDEPATH += src
# Input
HEADERS += curve.h \
geometry.h \
imagemanager.h \
layer.h \
layermanager.h \
linestring.h \
mapadapter.h \
mapcontrol.h \
mapnetwork.h \
point.h \
tilemapadapter.h \
wmsmapadapter.h \
circlepoint.h \
imagepoint.h \
gps_position.h \
osmmapadapter.h \
maplayer.h \
geometrylayer.h \
yahoomapadapter.h \
googlemapadapter.h \
googlesatmapadapter.h \
openaerialmapadapter.h \
fixedimageoverlay.h \
emptymapadapter.h
geometry.h \
imagemanager.h \
layer.h \
layermanager.h \
linestring.h \
mapadapter.h \
mapcontrol.h \
mapnetwork.h \
point.h \
tilemapadapter.h \
wmsmapadapter.h \
circlepoint.h \
imagepoint.h \
gps_position.h \
osmmapadapter.h \
maplayer.h \
geometrylayer.h \
yahoomapadapter.h \
googlemapadapter.h \
googlesatmapadapter.h \
openaerialmapadapter.h \
fixedimageoverlay.h \
emptymapadapter.h
SOURCES += curve.cpp \
geometry.cpp \
imagemanager.cpp \
layer.cpp \
layermanager.cpp \
linestring.cpp \
mapadapter.cpp \
mapcontrol.cpp \
mapnetwork.cpp \
point.cpp \
tilemapadapter.cpp \
wmsmapadapter.cpp \
circlepoint.cpp \
imagepoint.cpp \
gps_position.cpp \
osmmapadapter.cpp \
maplayer.cpp \
geometrylayer.cpp \
yahoomapadapter.cpp \
googlemapadapter.cpp \
googlesatmapadapter.cpp \
openaerialmapadapter.cpp \
fixedimageoverlay.cpp \
emptymapadapter.cpp
geometry.cpp \
imagemanager.cpp \
layer.cpp \
layermanager.cpp \
linestring.cpp \
mapadapter.cpp \
mapcontrol.cpp \
mapnetwork.cpp \
point.cpp \
tilemapadapter.cpp \
wmsmapadapter.cpp \
circlepoint.cpp \
imagepoint.cpp \
gps_position.cpp \
osmmapadapter.cpp \
maplayer.cpp \
geometrylayer.cpp \
yahoomapadapter.cpp \
googlemapadapter.cpp \
googlesatmapadapter.cpp \
openaerialmapadapter.cpp \
fixedimageoverlay.cpp \
emptymapadapter.cpp
......@@ -112,7 +112,8 @@ HEADERS += src/MG.h \
src/GAudioOutput.h \
src/LogCompressor.h \
src/ui/param/ParamTreeItem.h \
src/ui/param/ParamTreeModel.h
src/ui/param/ParamTreeModel.h \
src/ui/QGCParamWidget.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -159,5 +160,6 @@ SOURCES += src/main.cc \
src/GAudioOutput.cc \
src/LogCompressor.cc \
src/ui/param/ParamTreeItem.cc \
src/ui/param/ParamTreeModel.cc
src/ui/param/ParamTreeModel.cc \
src/ui/QGCParamWidget.cc
RESOURCES = mavground.qrc
......@@ -40,11 +40,14 @@ This file is part of the PIXHAWK project
#include <QStyleFactory>
#include <QAction>
#include <Core.h>
#include <MG.h>
#include <MainWindow.h>
#include "Core.h"
#include "MG.h"
#include "MainWindow.h"
#include "GAudioOutput.h"
#include "UDPLink.h"
#include "MAVLinkSimulationLink.h"
/**
* @brief Constructor for the main application.
......@@ -100,6 +103,43 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
// Remove splash screen
splashScreen->finish(mainWindow);
// Connect links
// to make sure that all components are initialized when the
// first messages arrive
UDPLink* udpLink = new UDPLink(QHostAddress::Any, 14550);
mainWindow->addLink(udpLink);
// Check if link could be connected
if (!udpLink->connect())
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not connect UDP port. Is already an instance of " + qAppName() + " running?");
msgBox.setInformativeText("You will not be able to receive data via UDP. Do you want to close the application?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Cancel);
int ret = msgBox.exec();
// Close the message box shortly after the click to prevent accidental clicks
QTimer::singleShot(5000, &msgBox, SLOT(reject()));
// Exit application
if (ret == QMessageBox::Yes)
{
qDebug() << "EXITING";
mainWindow->close();
this->exit(EXIT_SUCCESS);
}
}
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
mainWindow->addLink(simulationLink);
//CommConfigurationWindow* simulationWidget = new CommConfigurationWindow(simulationLink, mavlink, this);
//ui.menuNetwork->addAction(commWidget->getAction());
//simulationLink->connect();
}
/**
......
......@@ -174,7 +174,7 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
// Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Write message into buffer, prepending start sign
int len = message_to_send_buffer(buffer, &message);
int len = mavlink_msg_to_send_buffer(buffer, &message);
// If link is connected
if (link->isConnected())
{
......@@ -193,7 +193,7 @@ void MAVLinkProtocol::sendHeartbeat()
if (m_heartbeatsEnabled)
{
mavlink_message_t beat;
message_heartbeat_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID,&beat, OCU);
mavlink_msg_heartbeat_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID,&beat, OCU);
sendMessage(beat);
}
}
......
This diff is collapsed.
......@@ -115,7 +115,7 @@ protected:
int id;
QString name;
qint64 timeOffset;
sys_status_t status;
mavlink_sys_status_t status;
void enqueue(uint8_t* stream, uint8_t* index, mavlink_message_t* msg);
......
......@@ -91,14 +91,15 @@ bool MAVLinkXMLParser::generate()
QString commentContainer = "/**\n * @brief Send a %1 message\n *\n%2 * @return length of the message in bytes (excluding serial stream start sign)\n */\n";
QString commentEntry = " * @param %1 %2\n";
QString idDefine = QString("#define MAVLINK_MSG_ID_%1 %2").arg(messageName.toUpper(), QString::number(messageId));
QString cStructName = QString("%1_t").arg(messageName);
QString cStructName = QString("mavlink_%1_t").arg(messageName);
QString cStruct = "typedef struct __%1 \n{\n%2\n} %1;";
QString cStructLines = "";
QString encode = "static inline uint16_t message_%1_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const %2* %1)\n{\n\treturn message_%1_pack(%3);\n}\n";
QString encode = "static inline uint16_t mavlink_msg_%1_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const %2* %1)\n{\n\treturn mavlink_msg_%1_pack(%3);\n}\n";
QString decode = "static inline void message_%1_decode(const mavlink_message_t* msg, %2* %1)\n{\n%3}\n";
QString pack = "static inline uint16_t message_%1_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg%2)\n{\n\tmsg->msgid = MAVLINK_MSG_ID_%3;\n\tuint16_t i = 0;\n\n%4\n\treturn finalize_message(msg, system_id, component_id, i);\n}\n\n";
QString compactSend = "#if !defined(_WIN32) && !defined(__linux) && !defined(__APPLE__)\n\n#include \"global_data.h\"\n\nstatic inline void message_%3_send(%1 chan%5)\n{\n\t%2 msg;\n\tmessage_%3_pack(global_data.param[PARAM_SYSTEM_ID], global_data.param[PARAM_COMPONENT_ID], &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif";
QString decode = "static inline void mavlink_msg_%1_decode(const mavlink_message_t* msg, %2* %1)\n{\n%3}\n";
QString pack = "static inline uint16_t mavlink_msg_%1_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg%2)\n{\n\tmsg->msgid = MAVLINK_MSG_ID_%3;\n\tuint16_t i = 0;\n\n%4\n\treturn mavlink_finalize_message(msg, system_id, component_id, i);\n}\n\n";
QString compactSend = "#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_pack(mavlink_system.sysid, mavlink_system.compid, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif";
//QString compactStructSend = "#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_struct_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_encode(mavlink_system.sysid, mavlink_system.compid, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif";
QString unpacking = "";
QString prepends = "";
QString packParameters = "";
......@@ -135,7 +136,7 @@ bool MAVLinkXMLParser::generate()
// Add pack line to message_xx_pack function
packLines += QString("\ti += put_%1_by_index(%2, %3, i, msg->payload); //%4\n").arg(arrayType, fieldName, QString::number(arrayLength), e2.text());
// Add decode function for this type
decodeLines += QString("\tmessage_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName);
decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName);
}
else
// Handle simple types like integers and floats
......@@ -148,7 +149,7 @@ bool MAVLinkXMLParser::generate()
// Add pack line to message_xx_pack function
packLines += QString("\ti += put_%1_by_index(%2, i, msg->payload); //%3\n").arg(fieldType, fieldName, e2.text());
// Add decode function for this type
decodeLines += QString("\t%1->%2 = message_%1_get_%2(msg);\n").arg(messageName, fieldName);
decodeLines += QString("\t%1->%2 = mavlink_msg_%1_get_%2(msg);\n").arg(messageName, fieldName);
}
commentLines += commentEntry.arg(fieldName, fieldText);
QString unpackingComment = QString("/**\n * @brief Get field %1 from %2 message\n *\n * @return %3\n */\n").arg(fieldName, messageName, fieldText);
......@@ -184,14 +185,14 @@ bool MAVLinkXMLParser::generate()
// Array handling is different from simple types
if (fieldType.startsWith("array"))
{
unpacking += unpackingComment + QString("static inline uint16_t message_%1_get_%2(const mavlink_message_t* msg, int8_t* r_data)\n{\n%4\n}\n\n").arg(messageName, fieldName, unpackingCode);
unpacking += unpackingComment + QString("static inline uint16_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg, int8_t* r_data)\n{\n%4\n}\n\n").arg(messageName, fieldName, unpackingCode);
decodeLines += "";
QString arrayLength = QString(fieldType.split("[").at(1).split("]").first());
prepends += "+" + arrayLength;
}
else
{
unpacking += unpackingComment + QString("static inline %1 message_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg(fieldType, messageName, fieldName, unpackingCode);
unpacking += unpackingComment + QString("static inline %1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg(fieldType, messageName, fieldName, unpackingCode);
decodeLines += "";
prepends += "+sizeof(" + e2.attribute("type", "void") + ")";
}
......@@ -206,7 +207,7 @@ bool MAVLinkXMLParser::generate()
decode = decode.arg(messageName).arg(cStructName).arg(decodeLines);
compactSend = compactSend.arg(channelType, messageType, messageName, sendArguments, packParameters);
QString cFile = "// MESSAGE " + messageName.toUpper() + " PACKING\n\n" + idDefine + "\n\n" + cStruct + "\n\n" + commentContainer.arg(messageName.toLower(), commentLines) + pack + encode + "\n" + compactSend + "\n" + "// MESSAGE " + messageName.toUpper() + " UNPACKING\n\n" + unpacking + decode;
cFiles.append(qMakePair(QString("mavlink_message_%1.h").arg(messageName), cFile));
cFiles.append(qMakePair(QString("mavlink_msg_%1.h").arg(messageName), cFile));
}
}
}
......
This diff is collapsed.
......@@ -155,42 +155,6 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent)
joystick = new JoystickInput();
// HAS TO BE THE LAST ACTION
// to make sure that all components are initialized when the
// first messages arrive
udpLink = new UDPLink(QHostAddress::Any, 14550);
LinkManager::instance()->addProtocol(udpLink, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(udpLink, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction());
// Check if link could be connected
if (!udpLink->connect())
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not connect UDP port. Is already an instance of " + qAppName() + " running?");
msgBox.setInformativeText("Do you want to close the application?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Cancel);
int ret = msgBox.exec();
// Close the message box shortly after the click to prevent accidental clicks
QTimer::singleShot(5000, &msgBox, SLOT(reject()));
// Exit application
if (ret == QMessageBox::Yes)
{
qApp->exit(EXIT_SUCCESS);
}
}
simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
connect(simulationLink, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
LinkManager::instance()->addProtocol(simulationLink, mavlink);
//CommConfigurationWindow* simulationWidget = new CommConfigurationWindow(simulationLink, mavlink, this);
//ui.menuNetwork->addAction(commWidget->getAction());
//simulationLink->connect();
// Create actions
connectActions();
......@@ -309,7 +273,6 @@ void MainWindow::connectActions()
// Joystick configuration
connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
connect(ui.actionSimulate, SIGNAL(triggered(bool)), simulationLink, SLOT(connectLink(bool)));
}
void MainWindow::configure()
......@@ -333,6 +296,21 @@ void MainWindow::addLink()
// TODO Implement the link removal!
}
void MainWindow::addLink(LinkInterface *link)
{
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction());
LinkManager::instance()->addProtocol(link, mavlink);
// Special case for simulationlink
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim)
{
connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
}
}
void MainWindow::UASCreated(UASInterface* uas)
{
// Connect the UAS to the full user interface
......
......@@ -113,6 +113,7 @@ public slots:
void setLastAction(QString status);
void setLinkStatus(QString status);
void addLink();
void addLink(LinkInterface* link);
void configure();
void UASCreated(UASInterface* uas);
void startVideoCapture();
......
......@@ -9,29 +9,18 @@
ParameterInterface::ParameterInterface(QWidget *parent) :
QWidget(parent),
paramWidgets(new QMap<int, QGCParamWidget*>()),
curr(-1),
m_ui(new Ui::parameterWidget)
{
m_ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
components = new QMap<int, QTreeWidgetItem*>();
tree = new ParamTreeModel();
//treeView = new QTreeView(this);
//treeView->setModel(tree);
treeWidget = new QTreeWidget(this);
QStringList headerItems;
headerItems.append("Parameter");
headerItems.append("Value");
treeWidget->setHeaderLabels(headerItems);
QStackedWidget* stack = m_ui->stackedWidget;
//stack->addWidget(treeView);
//stack->setCurrentWidget(treeView);
stack->addWidget(treeWidget);
stack->setCurrentWidget(treeWidget);
// Setup UI connections
connect(m_ui->vehicleComboBox, SIGNAL(activated(int)), this, SLOT(selectUAS(int)));
connect(m_ui->readParamsButton, SIGNAL(clicked()), this, SLOT(requestParameterList()));
// Setup MAV connections
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
}
ParameterInterface::~ParameterInterface()
......@@ -39,6 +28,12 @@ ParameterInterface::~ParameterInterface()
delete m_ui;
}
void ParameterInterface::selectUAS(int index)
{
m_ui->stackedWidget->setCurrentIndex(index);
curr = index;
}
/**
*
* @param uas System to add to list
......@@ -47,26 +42,31 @@ void ParameterInterface::addUAS(UASInterface* uas)
{
m_ui->vehicleComboBox->addItem(uas->getUASName());
mav = uas;
// Setup UI connections
connect(m_ui->readParamsButton, SIGNAL(clicked()), this, SLOT(requestParameterList()));
QGCParamWidget* param = new QGCParamWidget(uas, this);
paramWidgets->insert(uas->getUASID(), param);
m_ui->stackedWidget->addWidget(param);
if (curr == -1)
{
m_ui->stackedWidget->setCurrentWidget(param);
curr = uas->getUASID();
qDebug() << "first widget";
}
// Connect signals
connect(uas, SIGNAL(parameterChanged(int,int,QString,float)), this, SLOT(receiveParameter(int,int,QString,float)));
//if (!paramViews.contains(uas))
//{
//uasViews.insert(uas, new UASView(uas, this));
//listLayout->addWidget(uasViews.value(uas));
//}
connect(uas, SIGNAL(parameterChanged(int,int,QString,float)), this, SLOT(addParameter(int,int,QString,float)));
}
void ParameterInterface::requestParameterList()
{
mav->requestParameters();
// Clear view
treeWidget->clear();
UASInterface* mav;
QGCParamWidget* widget = paramWidgets->value(curr);
if (widget != NULL)
{
mav = widget->getUAS();
mav->requestParameters();
// Clear view
widget->clear();
}
}
/**
......@@ -77,34 +77,20 @@ void ParameterInterface::requestParameterList()
*/
void ParameterInterface::addComponent(int uas, int component, QString componentName)
{
Q_UNUSED(uas);
QStringList list;
list.append(componentName);
list.append(QString::number(component));
QTreeWidgetItem* comp = new QTreeWidgetItem(list);
bool updated = false;
if (components->contains(component)) updated = true;
components->insert(component, comp);
if (!updated) treeWidget->addTopLevelItem(comp);
QGCParamWidget* widget = paramWidgets->value(uas);
if (widget != NULL)
{
widget->addComponent(component, componentName);
}
}
void ParameterInterface::receiveParameter(int uas, int component, QString parameterName, float value)
void ParameterInterface::addParameter(int uas, int component, QString parameterName, float value)
{
Q_UNUSED(uas);
// Insert parameter into map
//tree->appendParam(component, parameterName, value);
QStringList plist;
plist.append(parameterName);
plist.append(QString::number(value));
QTreeWidgetItem* item = new QTreeWidgetItem(plist);
// Get component
if (!components->contains(component))
QGCParamWidget* widget = paramWidgets->value(uas);
if (widget != NULL)
{
addComponent(uas, component, "Component #" + QString::number(component));
widget->addParameter(component, parameterName, value);
}
components->value(component)->addChild(item);
//treeWidget->addTopLevelItem(new QTreeWidgetItem(list));
}
/**
......@@ -126,6 +112,12 @@ void ParameterInterface::commitParameter(UASInterface* uas, int component, QStri
}
/*
void ParameterInterface::commitParameters(UASInterface* uas)
{
}*/
/**
*
*/
......
......@@ -8,6 +8,7 @@
#include "ui_ParameterInterface.h"
#include "UASInterface.h"
#include "ParamTreeModel.h"
#include "QGCParamWidget.h"
namespace Ui {
class ParameterInterface;
......@@ -21,20 +22,17 @@ public:
public slots:
void addUAS(UASInterface* uas);
void selectUAS(int index);
void addComponent(int uas, int component, QString componentName);
void receiveParameter(int uas, int component, QString parameterName, float value);
void addParameter(int uas, int component, QString parameterName, float value);
void requestParameterList();
void setParameter(UASInterface* uas, int component, QString parameterName, float value);
void commitParameter(UASInterface* uas, int component, QString parameterName, float value);
protected:
virtual void changeEvent(QEvent *e);
UASInterface* mav;
ParamTreeModel* tree;
QTreeView* treeView;
QTreeWidget* treeWidget;
QMap<int, QTreeWidgetItem*>* components;
QMap<int, QGCParamWidget*>* paramWidgets;
int curr;
private:
Ui::parameterWidget *m_ui;
......
#include <QHBoxLayout>
#include "QGCParamWidget.h"
#include "UASInterface.h"
#include <QDebug>
QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
QWidget(parent),
mav(uas),
components(new QMap<int, QTreeWidgetItem*>())
{
// Create tree widget
tree = new QTreeWidget(this);
// Set tree widget as widget onto this component
QHBoxLayout* horizontalLayout;
//form->setAutoFillBackground(false);
horizontalLayout = new QHBoxLayout(this);
horizontalLayout->setSpacing(0);
horizontalLayout->setMargin(0);
horizontalLayout->setSizeConstraint(QLayout::SetMinimumSize);
horizontalLayout->addWidget(tree);
this->setLayout(horizontalLayout);
// Set header
QStringList headerItems;
headerItems.append("Parameter");
headerItems.append("Value");
tree->setHeaderLabels(headerItems);
tree->setColumnCount(2);
}
UASInterface* QGCParamWidget::getUAS()
{
return mav;
}
/**
*
* @param uas System which has the component
* @param component id of the component
* @param componentName human friendly name of the component
*/
void QGCParamWidget::addComponent(int component, QString componentName)
{
QStringList list;
list.append(componentName);
list.append(QString::number(component));
QTreeWidgetItem* comp = new QTreeWidgetItem(list);
bool updated = false;
if (components->contains(component)) updated = true;
components->insert(component, comp);
if (!updated)
{
tree->addTopLevelItem(comp);
tree->update();
}
}
void QGCParamWidget::addParameter(int component, QString parameterName, float value)
{
// Insert parameter into map
//tree->appendParam(component, parameterName, value);
QStringList plist;
plist.append(parameterName);
plist.append(QString::number(value));
QTreeWidgetItem* item = new QTreeWidgetItem(plist);
// Get component
if (!components->contains(component))
{
addComponent(component, "Component #" + QString::number(component));
}
components->value(component)->addChild(item);
tree->update();
}
void QGCParamWidget::clear()
{
tree->clear();
}
#ifndef QGCPARAMWIDGET_H
#define QGCPARAMWIDGET_H
#include <QWidget>
#include <QTreeWidget>
#include <QTreeWidgetItem>
#include <QMap>
#include "UASInterface.h"
class QGCParamWidget : public QWidget
{
Q_OBJECT
public:
explicit QGCParamWidget(UASInterface* uas, QWidget *parent = 0);
UASInterface* getUAS();
signals:
public slots:
void addComponent(int component, QString componentName);
void addParameter(int component, QString parameterName, float value);
void clear();
protected:
UASInterface* mav;
QTreeWidget* tree;
QMap<int, QTreeWidgetItem*>* components;
};
#endif // QGCPARAMWIDGET_H
......@@ -83,10 +83,8 @@ void UASInfoWidget::addUAS(UASInterface* uas)
{
if (uas != NULL)
{
// connect(uas, SIGNAL(voltageChanged(int, double)), this, SLOT(setVoltage(int, double)));
connect(uas, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBattery(UASInterface*,double,double,int)));
connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(valueChanged(int,QString,double,quint64)));
connect(uas, SIGNAL(actuatorChanged(UASInterface*,int,double)), this, SLOT(actuatorChanged(UASInterface*,int,double)));
connect(uas, SIGNAL(dropRateChanged(int,float,float)), this, SLOT(updateDropRate(int,float,float)));
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateCPULoad(UASInterface*,double)));
// Set this UAS as active if it is the first one
......@@ -99,33 +97,6 @@ void UASInfoWidget::setActiveUAS(UASInterface* uas)
activeUAS = uas;
}
/*
void UASInfoWidget::actuatorChanged(UASInterface* uas, int actId, double value)
{
if (activeUAS == uas)
{
switch (actId)
{
case 0:
ui.topRotorLabel->setText(QString::number(value*3300, 'f', 2));
ui.topRotorBar->setValue(value * 100);
break;
case 1:
ui.botRotorLabel->setText(QString::number(value*3300, 'f', 2));
ui.botRotorBar->setValue(value * 100);
break;
case 2:
ui.leftServoLabel->setText(QString::number(value*57.2957795f, 'f', 2));
ui.leftServoBar->setValue((value * 50.0f) + 50);
break;
case 3:
ui.rightServoLabel->setText(QString::number(value*57.2957795f, 'f', 2));
ui.rightServoBar->setValue((value * 50.0f) + 50);
break;
}
}
}*/
void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
setVoltage(uas, voltage);
......@@ -147,67 +118,18 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
void UASInfoWidget::updateDropRate(int sysId, float receiveDrop, float sendDrop)
{
Q_UNUSED(sysId);
ui.receiveLossBar->setValue(receiveDrop * 100.0f);
ui.sendLossBar->setValue(sendDrop * 100.0f);
ui.receiveLossBar->setValue(receiveDrop);
ui.receiveLossLabel->setText(QString::number(receiveDrop) + "%");
ui.sendLossBar->setValue(sendDrop);
ui.sendLossLabel->setText(QString::number(receiveDrop) + "%");
}
//void UASInfoWidget::setBattery(int uasid, BatteryType type, int cells)
//{
// this->batteryType = type;
// this->cells = cells;
// switch (batteryType)
// {
// case NICD:
// break;
// case NIMH:
// break;
// case LIION:
// break;
// case LIPOLY:
// fullVoltage = this->cells * 4.18;
// emptyVoltage = this->cells * 3.4;
// break;
// case LIFE:
// break;
// case AGZN:
// break;
// }
//}
//double UASInfoWidget::calculateTimeRemaining() {
// quint64 dt = MG::TIME::getGroundTimeNow() - startTime;
// double seconds = dt / 1000.0f;
// double voltDifference = startVoltage - currentVoltage;
// if (voltDifference <= 0) voltDifference = 0.00000000001f;
// double dischargePerSecond = voltDifference / seconds;
// double remaining = (currentVoltage - emptyVoltage) / dischargePerSecond;
// // Can never be below 0
// if (remaining <= 0) remaining = 0.0000000000001f;
// return remaining;
//}
void UASInfoWidget::setVoltage(UASInterface* uas, double voltage)
{
Q_UNUSED(uas);
this->voltage = voltage;
}
//void UASInfoWidget::setVoltage(int uasid, double voltage)
//{
// // Read and update data
// currentVoltage = voltage;
// if (startVoltage == 0) startVoltage = currentVoltage;
// // This is a low pass filter to get smoother results: (0.8 * lastChargeLevel) + (0.2 * chargeLevel)
// double chargeLevel = (currentVoltage - emptyVoltage)/(fullVoltage - emptyVoltage);
// lastChargeLevel = (0.6 * lastChargeLevel) + (0.4 * chargeLevel);
//
// lastRemainingTime = calculateTimeRemaining();
//
// ui.voltageLabel->setText(QString::number(currentVoltage, 'f', voltageDecimals));
// setChargeLevel(0, lastChargeLevel * 100);
// setTimeRemaining(0, lastRemainingTime);
//}
void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel)
{
if (activeUAS == uas)
......@@ -231,20 +153,4 @@ void UASInfoWidget::refresh()
ui.loadLabel->setText(QString::number(this->load, 'f', loadDecimals));
ui.loadBar->setValue(static_cast<int>(this->load));
// if(this->timeRemaining > 1 && this->timeRemaining < MG::MAX_FLIGHT_TIME)
// {
// // Filter output to get a higher stability
// static int filterTime = static_cast<int>(this->timeRemaining);
// //filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining);
//
// int hours = filterTime % (60 * 60);
// int min = (filterTime - hours * 60) % 60;
// int sec = (filterTime - hours * 60 - min * 60);
// QString timeText;
// timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
// ui.voltageTimeEstimateLabel->setText(timeText);
// } else {
// ui.voltageTimeEstimateLabel->setText(tr("Calculating"));
// }
}
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