diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 225d5a7d8c9b9fb00f56fb7117aef9ff0b998647..a8aa4e0949f03d507f603f3f0b57caeb04b3dc92 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -147,7 +147,7 @@ void MAVLinkSimulationLink::mainloop() static float fullVoltage = 4.2 * 3; static float emptyVoltage = 3.35 * 3; static float voltage = fullVoltage; - static float drainRate = 0.0025; // x.xx% of the capacity is linearly drained per second + static float drainRate = 0.025; // x.xx% of the capacity is linearly drained per second attitude_t attitude; raw_aux_t rawAuxValues; @@ -352,7 +352,7 @@ void MAVLinkSimulationLink::mainloop() } statusCounter++; - status.vbat = voltage; + status.vbat = voltage * 1000; // millivolts // Pack message and get size of encoded byte string messageSize = message_sys_status_encode(systemId, componentId, &msg, &status); diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index aaba0648cfe06ae5d729f6f53d1a5fbb22cc36d7..46d6409723c70a4ba786ca76382983cbb2dcdb5e 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -52,8 +52,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : thrustSum(0), thrustMax(10), startVoltage(0), - currentVoltage(0.0f), - lpVoltage(0.0f), + currentVoltage(12.0f), + lpVoltage(12.0f), mode(MAV_MODE_UNINIT), status(MAV_STATE_UNINIT), onboardTimeOffset(0), diff --git a/src/ui/ParameterInterface.cc b/src/ui/ParameterInterface.cc index 4dc21b3332ff78c6c1ef667dc11f16220d71ea3a..c18c4df988127c37a897dab37746c6b79fdd1e8a 100644 --- a/src/ui/ParameterInterface.cc +++ b/src/ui/ParameterInterface.cc @@ -16,12 +16,20 @@ ParameterInterface::ParameterInterface(QWidget *parent) : tree = new ParamTreeModel(); - treeView = new QTreeView(this); - treeView->setModel(tree); + //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(treeView); + //stack->setCurrentWidget(treeView); + stack->addWidget(treeWidget); + stack->setCurrentWidget(treeWidget); } @@ -56,6 +64,8 @@ void ParameterInterface::addUAS(UASInterface* uas) void ParameterInterface::requestParameterList() { mav->requestParameters(); + // Clear view + treeWidget->clear(); } /** @@ -73,9 +83,11 @@ void ParameterInterface::receiveParameter(int uas, int component, QString parame { Q_UNUSED(uas); // Insert parameter into map - tree->appendParam(component, parameterName, value); - // Refresh view - treeView->update(); + //tree->appendParam(component, parameterName, value); + QStringList list; + list.append(parameterName); + list.append(QString::number(value)); + treeWidget->addTopLevelItem(new QTreeWidgetItem(list)); } /** diff --git a/src/ui/ParameterInterface.h b/src/ui/ParameterInterface.h index 7da36303cdefa4f9583b48baf93469a2c42bcbe6..266014d3ed3ecf6c91daaf7d15a803f30db20ffb 100644 --- a/src/ui/ParameterInterface.h +++ b/src/ui/ParameterInterface.h @@ -3,6 +3,7 @@ #include #include +#include #include "ui_ParameterInterface.h" #include "UASInterface.h" #include "ParamTreeModel.h" @@ -31,6 +32,7 @@ protected: UASInterface* mav; ParamTreeModel* tree; QTreeView* treeView; + QTreeWidget* treeWidget; private: Ui::parameterWidget *m_ui; diff --git a/src/ui/param/ParamTreeItem.cc b/src/ui/param/ParamTreeItem.cc index 29cd8815bf1d24f433e69ed3b45721dd8939c7a7..40972e37411c688edf0ab7409d09e98afa37e4fb 100644 --- a/src/ui/param/ParamTreeItem.cc +++ b/src/ui/param/ParamTreeItem.cc @@ -107,11 +107,16 @@ QVariant ParamTreeItem::data(int column) const } } -ParamTreeItem *ParamTreeItem::parent() +ParamTreeItem *ParamTreeItem::parent() const { return parentItem; } +const QList* ParamTreeItem::children() const +{ + return &childItems; +} + int ParamTreeItem::row() const { if (parentItem) diff --git a/src/ui/param/ParamTreeItem.h b/src/ui/param/ParamTreeItem.h index 1b9f6ab5478e7d7c112562ba9f73575751930c12..3ba8b3e03a9d56d4461cb9c03888dfb81ad69a73 100644 --- a/src/ui/param/ParamTreeItem.h +++ b/src/ui/param/ParamTreeItem.h @@ -53,7 +53,8 @@ public: int columnCount() const; QVariant data(int column) const; int row() const; - ParamTreeItem *parent(); + ParamTreeItem *parent() const; + const QList* children() const; protected: QString paramName; diff --git a/src/ui/param/ParamTreeModel.cc b/src/ui/param/ParamTreeModel.cc index b3484ff81352527c4a6d8cfe4c64ba89d18671f3..fa991ee5770bd055035213da3e1994b97a0e50c2 100644 --- a/src/ui/param/ParamTreeModel.cc +++ b/src/ui/param/ParamTreeModel.cc @@ -172,11 +172,11 @@ void ParamTreeModel::appendComponent(int componentId) ParamTreeItem* item = new ParamTreeItem(QString("Component #") + QString::number(componentId) + QString(""), 0, rootItem); components.insert(componentId, item); } + //emit dataChanged(); } void ParamTreeModel::appendParam(int componentId, QString name, float value) { - // If component does not exist yet if (!components.contains(componentId)) { @@ -186,6 +186,7 @@ void ParamTreeModel::appendParam(int componentId, QString name, float value) // FIXME Children may be double here comp->appendChild(new ParamTreeItem(name, value, comp)); qDebug() << __FILE__ << __LINE__ << "Added param" << name << value << "for component" << comp->getParamName(); + emit dataChanged(createIndex(0, 0, rootItem), createIndex(0, 0, rootItem)); } void ParamTreeModel::setupModelData(const QStringList &lines, ParamTreeItem *parent)