Commit 9ac93ce9 authored by lm's avatar lm

Working on new parameter view and interface

parent 451457ba
......@@ -112,7 +112,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// it's first messages.
// First create new UAS object
uas = new UAS(message.sysid);
uas = new UAS(this, message.sysid);
// Make UAS aware that this link can be used to communicate with the actual robot
uas->addLink(link);
// Connect this robot to the UAS object
......@@ -137,6 +137,18 @@ QString MAVLinkProtocol::getName()
return QString(tr("MAVLink protocol"));
}
/** @return System id of this application */
int getSystemId()
{
return MG::SYSTEM::ID;
}
/** @return Component id of this application */
int getComponentId()
{
return MG::SYSTEM::COMPID;
}
/**
* @param message message to send
*/
......
......@@ -56,6 +56,10 @@ public:
void run();
/** @brief Get the human-friendly name of this protocol */
QString getName();
/** @brief Get the system id of this application */
int getSystemId();
/** @brief Get the component id of this application */
int getComponentId();
/** @brief The auto heartbeat emission rate in Hertz */
int getHeartbeatRate();
/** @brief Get heartbeat state */
......
......@@ -40,9 +40,10 @@ This file is part of the PIXHAWK project
#include "UASManager.h"
#include "MG.h"
#include "GAudioOutput.h"
#include "mavlink.h"
#include "MAVLinkProtocol.h"
#include <mavlink.h>
UAS::UAS(int id=0) :
UAS::UAS(MAVLinkProtocol* protocol, int id) :
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
......@@ -69,6 +70,7 @@ UAS::UAS(int id=0) :
{
uasId = id;
setBattery(LIPOLY, 3);
mavlink = protocol;
}
UAS::~UAS()
......@@ -523,6 +525,12 @@ void UAS::requestWaypoints()
qDebug() << "UAS Request WPs";
}
void UAS::requestParameters()
{
mavlink_message_t msg;
message_param_request_read_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, 0);
}
/**
* @brief Launches the system
*
......
......@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project
#include "UASInterface.h"
#include "MG.h"
#include <MAVLinkProtocol.h>
#include <mavlink.h>
/**
......@@ -47,7 +48,7 @@ This file is part of the PIXHAWK project
class UAS : public UASInterface {
Q_OBJECT
public:
UAS(int id);
UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS();
enum BatteryType {
......@@ -84,6 +85,7 @@ protected:
int uasId; ///< Unique system ID
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
BatteryType batteryType; ///< The battery type
int cells; ///< Number of cells
......@@ -150,6 +152,7 @@ public slots:
void shutdown();
void requestWaypoints();
void requestParameters();
void clearWaypointList();
/** @brief Enable the motors */
void enable_motors();
......
......@@ -167,14 +167,12 @@ public slots:
* Works only if already landed and will cleanly shut down all onboard computers.
*/
virtual void shutdown() = 0;
/**
* @brief Request the list of stored waypoints from the robot
*/
/** @brief Request the list of stored waypoints from the robot */
virtual void requestWaypoints() = 0;
/**
* @brief Clear all existing waypoints on the robot
*/
/** @brief Clear all existing waypoints on the robot */
virtual void clearWaypointList() = 0;
/** @brief Request all onboard parameters of all components */
virtual void requestParameters() = 0;
/**
* @brief Add a link to the list of current links
......
......@@ -162,7 +162,27 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent)
LinkManager::instance()->addProtocol(udpLink, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(udpLink, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction());
udpLink->connect();
// 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)));
......
......@@ -46,6 +46,11 @@ void ParameterInterface::addUAS(UASInterface* uas)
//}
}
void ParameterInterface::requestParameterList()
{
mav->requestParameters();
}
/**
*
* @param uas System which has the component
......
......@@ -19,12 +19,15 @@ public slots:
void addUAS(UASInterface* uas);
void addComponent(UASInterface* uas, int component, QString componentName);
void receiveParameter(UASInterface* 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;
private:
Ui::parameterWidget *m_ui;
};
......
......@@ -34,7 +34,8 @@ This file is part of the PIXHAWK project
#include "ParamTreeModel.h"
ParamTreeModel::ParamTreeModel(QObject *parent)
: QAbstractItemModel(parent)
: QAbstractItemModel(parent),
components()
{
QList<QVariant> rootData;
rootData << tr("ID") << tr("Parameter") << tr("Value");
......@@ -43,7 +44,8 @@ ParamTreeModel::ParamTreeModel(QObject *parent)
}
ParamTreeModel::ParamTreeModel(const QString &data, QObject *parent)
: QAbstractItemModel(parent)
: QAbstractItemModel(parent),
components()
{
QList<QVariant> rootData;
rootData << tr("Parameter") << tr("Value");
......@@ -86,7 +88,7 @@ Qt::ItemFlags ParamTreeModel::flags(const QModelIndex &index) const
}
QVariant ParamTreeModel::headerData(int section, Qt::Orientation orientation,
int role) const
int role) const
{
if (orientation == Qt::Horizontal && role == Qt::DisplayRole)
return rootItem->data(section);
......@@ -95,7 +97,7 @@ QVariant ParamTreeModel::headerData(int section, Qt::Orientation orientation,
}
QModelIndex ParamTreeModel::index(int row, int column, const QModelIndex &parent)
const
const
{
if (!hasIndex(row, column, parent))
return QModelIndex();
......@@ -142,6 +144,33 @@ int ParamTreeModel::rowCount(const QModelIndex &parent) const
return parentItem->childCount();
}
ParamTreeItem* ParamTreeModel::getNodeForComponentId(int id)
{
return components.value(id);
}
void ParamTreeModel::appendComponent(int componentId, QString name)
{
if (!components.contains(componentId))
{
ParamTreeItem* item = new ParamTreeItem(componentId, name, 0, rootItem);
components.insert(componentId, item);
}
}
void ParamTreeModel::appendParam(int componentId, int id, QString name, float value)
{
ParamTreeItem* comp = components.value(componentId);
// If component does not exist yet
if (comp == NULL)
{
appendComponent(componentId, name);
comp = components.value(componentId);
}
// FIXME Children may be double here
comp->appendChild(new ParamTreeItem(id, name, value, comp));
}
void ParamTreeModel::setupModelData(const QStringList &lines, ParamTreeItem *parent)
{
QList<ParamTreeItem*> parents;
......
......@@ -42,7 +42,7 @@ class ParamTreeModel : public QAbstractItemModel
Q_OBJECT
public:
ParamTreeModel::ParamTreeModel(QObject *parent = 0);
ParamTreeModel(QObject *parent = 0);
ParamTreeModel(const QString &data, QObject *parent = 0);
~ParamTreeModel();
......@@ -57,7 +57,15 @@ public:
int columnCount(const QModelIndex &parent = QModelIndex()) const;
public slots:
void appendParam(int id, QString name, float value);
/** @brief Add a new parameter */
void appendParam(int componentId, int id, QString name, float value);
/** @brief Add a new component for this system */
void appendComponent(int componentId, QString name);
protected:
ParamTreeItem* getNodeForComponentId(int id);
QMap<int, ParamTreeItem*> components;
private:
void setupModelData(const QStringList &lines, ParamTreeItem *parent);
......
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