QGCParamWidget.cc 24.9 KB
Newer Older
1 2 3 4
/*=====================================================================

QGroundControl Open Source Ground Control Station

pixhawk's avatar
pixhawk committed
5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28

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 Implementation of class QGCParamWidget
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
 */

29 30
#include <QGridLayout>
#include <QPushButton>
31 32
#include <QFileDialog>
#include <QFile>
33
#include <QList>
34
#include <QSettings>
pixhawk's avatar
pixhawk committed
35 36 37 38

#include "QGCParamWidget.h"
#include "UASInterface.h"
#include <QDebug>
39
#include "QGC.h"
pixhawk's avatar
pixhawk committed
40

41 42 43 44
/**
 * @param uas MAV to set the parameters on
 * @param parent Parent widget
 */
pixhawk's avatar
pixhawk committed
45
QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
46
        QWidget(parent),
lm's avatar
lm committed
47

48
        mav(uas),
lm's avatar
lm committed
49
        components(new QMap<int, QTreeWidgetItem*>()),
pixhawk's avatar
pixhawk committed
50
        paramGroups(),
51
        changedValues(),
lm's avatar
lm committed
52 53 54
        parameters(),
        transmissionListMode(false),
        transmissionActive(false),
55 56 57
        transmissionStarted(0),
        retransmissionTimeout(350),
        rewriteTimeout(500)
pixhawk's avatar
pixhawk committed
58
{
59 60 61
    // Load settings
    loadSettings();

pixhawk's avatar
pixhawk committed
62 63
    // Create tree widget
    tree = new QTreeWidget(this);
lm's avatar
lm committed
64
    statusLabel = new QLabel();
65
    tree->setColumnWidth(0, 150);
pixhawk's avatar
pixhawk committed
66 67

    // Set tree widget as widget onto this component
68
    QGridLayout* horizontalLayout;
pixhawk's avatar
pixhawk committed
69
    //form->setAutoFillBackground(false);
70 71
    horizontalLayout = new QGridLayout(this);
    horizontalLayout->setSpacing(6);
pixhawk's avatar
pixhawk committed
72 73 74
    horizontalLayout->setMargin(0);
    horizontalLayout->setSizeConstraint(QLayout::SetMinimumSize);

lm's avatar
lm committed
75
    // Parameter tree
76
    horizontalLayout->addWidget(tree, 0, 0, 1, 3);
lm's avatar
lm committed
77 78 79 80 81 82 83

    // Status line
    statusLabel->setText(tr("Click read to get parameters"));
    horizontalLayout->addWidget(statusLabel, 1, 0, 1, 3);


    // BUTTONS
84
    QPushButton* refreshButton = new QPushButton(tr("Refresh"));
85 86
    refreshButton->setToolTip(tr("Load parameters currently in non-permanent memory of aircraft."));
    refreshButton->setWhatsThis(tr("Load parameters currently in non-permanent memory of aircraft."));
87
    connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestParameterList()));
lm's avatar
lm committed
88
    horizontalLayout->addWidget(refreshButton, 2, 0);
89

90
    QPushButton* setButton = new QPushButton(tr("Transmit"));
91 92
    setButton->setToolTip(tr("Set current parameters in non-permanent onboard memory"));
    setButton->setWhatsThis(tr("Set current parameters in non-permanent onboard memory"));
93
    connect(setButton, SIGNAL(clicked()), this, SLOT(setParameters()));
lm's avatar
lm committed
94
    horizontalLayout->addWidget(setButton, 2, 1);
95

96
    QPushButton* writeButton = new QPushButton(tr("Write (ROM)"));
97 98
    writeButton->setToolTip(tr("Copy current parameters in non-permanent memory of the aircraft to permanent memory. Transmit your parameters first to write these."));
    writeButton->setWhatsThis(tr("Copy current parameters in non-permanent memory of the aircraft to permanent memory. Transmit your parameters first to write these."));
99
    connect(writeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
lm's avatar
lm committed
100
    horizontalLayout->addWidget(writeButton, 2, 2);
101

102
    QPushButton* loadFileButton = new QPushButton(tr("Load File"));
103 104
    loadFileButton->setToolTip(tr("Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them."));
    loadFileButton->setWhatsThis(tr("Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them."));
105
    connect(loadFileButton, SIGNAL(clicked()), this, SLOT(loadParameters()));
lm's avatar
lm committed
106
    horizontalLayout->addWidget(loadFileButton, 3, 0);
107 108

    QPushButton* saveFileButton = new QPushButton(tr("Save File"));
109 110
    saveFileButton->setToolTip(tr("Save parameters in this view to a file on this computer."));
    saveFileButton->setWhatsThis(tr("Save parameters in this view to a file on this computer."));
111
    connect(saveFileButton, SIGNAL(clicked()), this, SLOT(saveParameters()));
lm's avatar
lm committed
112 113 114 115 116 117 118
    horizontalLayout->addWidget(saveFileButton, 3, 1);

    QPushButton* readButton = new QPushButton(tr("Read (ROM)"));
    readButton->setToolTip(tr("Copy parameters from permanent memory to non-permanent current memory of aircraft. DOES NOT update the parameters in this view, click refresh after copying them to get them."));
    readButton->setWhatsThis(tr("Copy parameters from permanent memory to non-permanent current memory of aircraft. DOES NOT update the parameters in this view, click refresh after copying them to get them."));
    connect(readButton, SIGNAL(clicked()), this, SLOT(readParameters()));
    horizontalLayout->addWidget(readButton, 3, 2);
119

120
    // Set layout
pixhawk's avatar
pixhawk committed
121 122 123 124 125 126 127 128
    this->setLayout(horizontalLayout);

    // Set header
    QStringList headerItems;
    headerItems.append("Parameter");
    headerItems.append("Value");
    tree->setHeaderLabels(headerItems);
    tree->setColumnCount(2);
129
    tree->setExpandsOnDoubleClick(true);
130 131 132

    // Connect signals/slots
    connect(this, SIGNAL(parameterChanged(int,QString,float)), mav, SLOT(setParameter(int,QString,float)));
133
    connect(tree, SIGNAL(itemChanged(QTreeWidgetItem*,int)), this, SLOT(parameterItemChanged(QTreeWidgetItem*,int)));
lm's avatar
lm committed
134

135
    // New parameters from UAS
lm's avatar
lm committed
136
    connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,float)), this, SLOT(addParameter(int,int,int,int,QString,float)));
137 138 139 140

    // Connect retransmission guard
    connect(this, SIGNAL(requestParameter(int,int)), uas, SLOT(requestParameter(int,int)));
    connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick()));
pixhawk's avatar
pixhawk committed
141 142
}

143 144 145 146 147 148 149 150 151 152 153 154
void QGCParamWidget::loadSettings()
{
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
    bool ok;
    int temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", retransmissionTimeout).toInt(&ok);
    if (ok) retransmissionTimeout = temp;
    temp = settings.value("PARAMETER_REWRITE_TIMEOUT", rewriteTimeout).toInt(&ok);
    if (ok) rewriteTimeout = temp;
    settings.endGroup();
}

155 156 157 158
/**
 * @return The MAV of this widget. Unless the MAV object has been destroyed, this
 *         pointer is never zero.
 */
pixhawk's avatar
pixhawk committed
159 160 161 162 163 164 165 166 167 168 169
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
 */
170
void QGCParamWidget::addComponent(int uas, int component, QString componentName)
pixhawk's avatar
pixhawk committed
171
{
172
    Q_UNUSED(uas);
pixhawk's avatar
pixhawk committed
173
    if (components->contains(component))
pixhawk's avatar
pixhawk committed
174
    {
pixhawk's avatar
pixhawk committed
175 176 177 178 179 180 181 182 183 184 185 186 187 188
        // Update existing
        components->value(component)->setData(0, Qt::DisplayRole, componentName);
        components->value(component)->setData(1, Qt::DisplayRole, QString::number(component));
    }
    else
    {
        // Add new
        QStringList list;
        list.append(componentName);
        list.append(QString::number(component));
        QTreeWidgetItem* comp = new QTreeWidgetItem(list);
        components->insert(component, comp);
        // Create grouping and update maps
        paramGroups.insert(component, new QMap<QString, QTreeWidgetItem*>());
pixhawk's avatar
pixhawk committed
189 190
        tree->addTopLevelItem(comp);
        tree->update();
191 192 193 194 195 196 197 198 199 200
        // Create map in parameters
        if (!parameters.contains(component))
        {
            parameters.insert(component, new QMap<QString, float>());
        }
        // Create map in changed parameters
        if (!changedValues.contains(component))
        {
            changedValues.insert(component, new QMap<QString, float>());
        }
pixhawk's avatar
pixhawk committed
201 202 203
    }
}

lm's avatar
lm committed
204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227
/**
 * @param uas System which has the component
 * @param component id of the component
 * @param parameterName human friendly name of the parameter
 */
void QGCParamWidget::addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, float value)
{
    addParameter(uas, component, parameterName, value);

    // List mode is different from single parameter transfers
    if (transmissionListMode)
    {
        // Only accept the list size once on the first packet from
        // each component
        if (!transmissionListSizeKnown.contains(component))
        {
            // If this was the first packet to announce the list size
            // set all packets not received yet as missing to enforce
            // retransmission until full list is received
            if (!transmissionMissingPackets.contains(component))
            {
                transmissionMissingPackets.insert(component, new QList<int>());
            }

228
            // Mark all parameters as missing
lm's avatar
lm committed
229 230 231 232 233 234 235
            for (int i = 0; i < paramCount; ++i)
            {
                if (!transmissionMissingPackets.value(component)->contains(i))
                {
                    transmissionMissingPackets.value(component)->append(i);
                }
            }
236 237

            // Mark list size as known
lm's avatar
lm committed
238 239
            transmissionListSizeKnown.insert(component, true);
        }
lm's avatar
lm committed
240 241 242 243

        // Start retransmission guard
        // or reset timer
        setRetransmissionGuardEnabled(true);
lm's avatar
lm committed
244 245 246 247 248 249 250
    }

    // Mark this parameter as received
    int index = transmissionMissingPackets.value(component)->indexOf(paramId);
    // If the MAV sent the parameter without request, it wont be in missing list
    if (index != -1) transmissionMissingPackets.value(component)->removeAt(index);

251 252 253 254 255 256 257
    int missCount = 0;
    foreach (int key, transmissionMissingPackets.keys())
    {
        missCount +=  transmissionMissingPackets.value(key)->count();
    }

    statusLabel->setText(tr("Got Param (#%1 of %5) %2: %3 (%4 missing)").arg(paramId+1).arg(parameterName).arg(value).arg(missCount).arg(paramCount));
lm's avatar
lm committed
258 259

    // Check if last parameter was received
260
    if (missCount == 0)
lm's avatar
lm committed
261 262 263 264 265 266 267 268 269 270 271
    {
        this->transmissionActive = false;
        this->transmissionListMode = false;
        transmissionListSizeKnown.clear();
        foreach (int key, transmissionMissingPackets.keys())
        {
            transmissionMissingPackets.value(key)->clear();
        }
    }
}

272 273 274 275 276 277
/**
 * @param uas System which has the component
 * @param component id of the component
 * @param parameterName human friendly name of the parameter
 */
void QGCParamWidget::addParameter(int uas, int component, QString parameterName, float value)
pixhawk's avatar
pixhawk committed
278
{
279
    Q_UNUSED(uas);
280
    // Reference to item in tree
281
    QTreeWidgetItem* parameterItem = NULL;
pixhawk's avatar
pixhawk committed
282 283 284 285

    // Get component
    if (!components->contains(component))
    {
286 287 288 289 290 291 292 293 294 295 296 297 298 299 300
        QString componentName;
        switch (component)
        {
        case MAV_COMP_ID_CAMERA:
            componentName = tr("Camera (#%1)").arg(component);
            break;
        case MAV_COMP_ID_IMU:
            componentName = tr("IMU (#%1)").arg(component);
            break;
        default:
            componentName = tr("Component #").arg(component);
            break;
        }

        addComponent(uas, component, componentName);
pixhawk's avatar
pixhawk committed
301
    }
302

303 304 305 306 307 308 309
    // Replace value in map

    // FIXME
    if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
    parameters.value(component)->insert(parameterName, value);


pixhawk's avatar
pixhawk committed
310 311 312
    QString splitToken = "_";
    // Check if auto-grouping can work
    if (parameterName.contains(splitToken))
313
    {
pixhawk's avatar
pixhawk committed
314 315 316
        QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty);
        QMap<QString, QTreeWidgetItem*>* compParamGroups = paramGroups.value(component);
        if (!compParamGroups->contains(parent))
317
        {
pixhawk's avatar
pixhawk committed
318 319 320 321 322 323
            // Insert group item
            QStringList glist;
            glist.append(parent);
            QTreeWidgetItem* item = new QTreeWidgetItem(glist);
            compParamGroups->insert(parent, item);
            components->value(component)->addChild(item);
324
        }
325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347

        // Append child to group
        bool found = false;
        QTreeWidgetItem* parentItem = compParamGroups->value(parent);
        for (int i = 0; i < parentItem->childCount(); i++)
        {
            QTreeWidgetItem* child = parentItem->child(i);
            QString key = child->data(0, Qt::DisplayRole).toString();
            if (key == parameterName)
            {
                //qDebug() << "UPDATED CHILD";
                parameterItem = child;
                parameterItem->setData(1, Qt::DisplayRole, value);
                found = true;
            }
        }

        if (!found)
        {
            // Insert parameter into map
            QStringList plist;
            plist.append(parameterName);
            plist.append(QString::number(value));
348
            // CREATE PARAMETER ITEM
349
            parameterItem = new QTreeWidgetItem(plist);
350
            // CONFIGURE PARAMETER ITEM
351 352

            compParamGroups->value(parent)->addChild(parameterItem);
lm's avatar
lm committed
353
            parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
354
        }
355
    }
pixhawk's avatar
pixhawk committed
356
    else
357
    {
pixhawk's avatar
pixhawk committed
358 359 360 361 362 363 364 365 366
        bool found = false;
        QTreeWidgetItem* parent = components->value(component);
        for (int i = 0; i < parent->childCount(); i++)
        {
            QTreeWidgetItem* child = parent->child(i);
            QString key = child->data(0, Qt::DisplayRole).toString();
            if (key == parameterName)
            {
                //qDebug() << "UPDATED CHILD";
367 368
                parameterItem = child;
                parameterItem->setData(1, Qt::DisplayRole, value);
pixhawk's avatar
pixhawk committed
369 370 371 372 373 374
                found = true;
            }
        }

        if (!found)
        {
375 376 377 378
            // Insert parameter into map
            QStringList plist;
            plist.append(parameterName);
            plist.append(QString::number(value));
379
            // CREATE PARAMETER ITEM
380
            parameterItem = new QTreeWidgetItem(plist);
381
            // CONFIGURE PARAMETER ITEM
382

lm's avatar
lm committed
383 384
            components->value(component)->addChild(parameterItem);
            parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
pixhawk's avatar
pixhawk committed
385
        }
386
        //tree->expandAll();
387
    }
388
    // Reset background color
389 390 391
    parameterItem->setBackground(0, QBrush(QColor(0, 0, 0)));
    parameterItem->setBackground(1, Qt::NoBrush);
    //tree->update();
pixhawk's avatar
pixhawk committed
392
    if (changedValues.contains(component)) changedValues.value(component)->remove(parameterName);
pixhawk's avatar
pixhawk committed
393 394
}

395 396 397 398
/**
 * Send a request to deliver the list of onboard parameters
 * to the MAV.
 */
399 400
void QGCParamWidget::requestParameterList()
{
401 402 403 404 405 406 407
    // FIXME This call does not belong here
    // Once the comm handling is moved to a new
    // Param manager class the settings can be directly
    // loaded from MAVLink protocol
    loadSettings();
    // End of FIXME

lm's avatar
lm committed
408
    // Clear view and request param list
409
    clear();
410
    parameters.clear();
lm's avatar
lm committed
411
    received.clear();
lm's avatar
lm committed
412 413 414 415 416 417 418 419 420
    // Clear transmission state
    transmissionListMode = true;
    transmissionListSizeKnown.clear();
    foreach (int key, transmissionMissingPackets.keys())
    {
        transmissionMissingPackets.value(key)->clear();
    }
    transmissionActive = true;
    transmissionStarted = QGC::groundTimeUsecs();
lm's avatar
lm committed
421
    mav->requestParameters();
422 423
}

424
void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
lm's avatar
lm committed
425
{
426
    if (current && column > 0)
lm's avatar
lm committed
427
    {
428 429 430 431 432 433 434 435 436 437 438 439 440
        QTreeWidgetItem* parent = current->parent();
        while (parent->parent() != NULL)
        {
            parent = parent->parent();
        }
        // Parent is now top-level component
        int key = components->key(parent);
        if (!changedValues.contains(key))
        {
            changedValues.insert(key, new QMap<QString, float>());
        }
        QMap<QString, float>* map = changedValues.value(key, NULL);
        if (map)
lm's avatar
lm committed
441
        {
442 443 444
            bool ok;
            QString str = current->data(0, Qt::DisplayRole).toString();
            float value = current->data(1, Qt::DisplayRole).toDouble(&ok);
lm's avatar
lm committed
445
            // Set parameter on changed list to be transmitted to MAV
446
            if (ok)
lm's avatar
lm committed
447
            {
448 449
                if (ok)
                {
lm's avatar
lm committed
450 451
                    statusLabel->setText(tr("Changed Param %1:%2: %3").arg(key).arg(str).arg(value));
                    //qDebug() << "PARAM CHANGED: COMP:" << key << "KEY:" << str << "VALUE:" << value;
452
                    // Changed values list
453
                    if (map->contains(str)) map->remove(str);
454
                    map->insert(str, value);
455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497

                    // Check if the value was numerically changed
                    if (!parameters.value(key)->contains(str) || parameters.value(key)->value(str, 0.0f) != value)
                    {
                        current->setBackground(0, QBrush(QColor(QGC::colorGreen)));
                        current->setBackground(1, QBrush(QColor(QGC::colorGreen)));
                    }

                    // All parameters list
                    if (parameters.value(key)->contains(str)) parameters.value(key)->remove(str);
                    parameters.value(key)->insert(str, value);
                }
            }
        }
    }
}

void QGCParamWidget::saveParameters()
{    
    QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./parameters.txt", tr("Parameter File (*.txt)"));
    QFile file(fileName);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
    {
        return;
    }

    QTextStream in(&file);

    in << "# Onboard parameters for system " << mav->getUASName() << "\n";
    in << "#\n";
    in << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    // Iterate through all components, through all parameters and emit them
    QMap<int, QMap<QString, float>*>::iterator i;
    for (i = parameters.begin(); i != parameters.end(); ++i)
    {
        // Iterate through the parameters of the component
        int compid = i.key();
        QMap<QString, float>* comp = i.value();
        {
            QMap<QString, float>::iterator j;
            for (j = comp->begin(); j != comp->end(); ++j)
            {
498
                QString paramValue("%1");
lm's avatar
lm committed
499
                paramValue = paramValue.arg(j.value(), 25, 'g', 12);
500
                in << mav->getUASID() << "\t" << compid << "\t" << j.key() << "\t" << paramValue << "\n";
501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529
                in.flush();
            }
        }
    }
    file.close();
}

void QGCParamWidget::loadParameters()
{
    QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Parameter file (*.txt)"));
    QFile file(fileName);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

    // Clear list
    clear();

    QTextStream in(&file);
    while (!in.atEnd())
    {
        QString line = in.readLine();
        if (!line.startsWith("#"))
        {
            QStringList wpParams = line.split("\t");
            if (wpParams.size() == 4)
            {
                // Only load parameters for right mav
                if (mav->getUASID() == wpParams.at(0).toInt())
                {
pixhawk's avatar
pixhawk committed
530

lm's avatar
lm committed
531 532 533 534 535 536 537 538 539
                    bool changed = false;
                    int component = wpParams.at(1).toInt();
                    QString parameterName = wpParams.at(2);
                    if (!parameters.contains(component) || parameters.value(component)->value(parameterName, 0.0f) != (float)wpParams.at(3).toDouble())
                    {
                        changed = true;
                    }

                    // Set parameter value
540
                    addParameter(wpParams.at(0).toInt(), wpParams.at(1).toInt(), wpParams.at(2), wpParams.at(3).toDouble());
lm's avatar
lm committed
541 542

                    if (changed)
543
                    {
lm's avatar
lm committed
544 545
                        // Create changed values data structure if necessary
                        if (!changedValues.contains(wpParams.at(1).toInt()))
546
                        {
lm's avatar
lm committed
547
                            changedValues.insert(wpParams.at(1).toInt(), new QMap<QString, float>());
548 549
                        }

lm's avatar
lm committed
550 551 552 553 554 555 556 557
                        // Add to changed values
                        if (changedValues.value(wpParams.at(1).toInt())->contains(wpParams.at(2)))
                        {
                            changedValues.value(wpParams.at(1).toInt())->remove(wpParams.at(2));
                        }

                        changedValues.value(wpParams.at(1).toInt())->insert(wpParams.at(2), (float)wpParams.at(3).toDouble());

558
                        //qDebug() << "MARKING COMP" << wpParams.at(1).toInt() << "PARAM" << wpParams.at(2) << "VALUE" << (float)wpParams.at(3).toDouble() << "AS CHANGED";
lm's avatar
lm committed
559 560

                        // Mark in UI
pixhawk's avatar
pixhawk committed
561

pixhawk's avatar
pixhawk committed
562

563
                    }
564
                }
lm's avatar
lm committed
565 566
            }
        }
567
    }
568 569
    file.close();

lm's avatar
lm committed
570 571
}

572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608
/**
 * Enabling the retransmission guard enables the parameter widget to track
 * dropped parameters and to re-request them. This works for both individual
 * parameter reads as well for whole list requests.
 *
 * @param enabled True if retransmission checking should be enabled, false else
 */
void QGCParamWidget::setRetransmissionGuardEnabled(bool enabled)
{
    if (enabled)
    {
        retransmissionTimer.start(retransmissionTimeout);
    }
    else
    {
        retransmissionTimer.stop();
    }
}

void QGCParamWidget::retransmissionGuardTick()
{
    if (transmissionActive)
    {
        qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS..";
        // Re-request at maximum five parameters at once
        // to prevent link flooding

        QMap<int, QMap<QString, float>*>::iterator i;
        for (i = parameters.begin(); i != parameters.end(); ++i)
        {
            // Iterate through the parameters of the component
            int component = i.key();
            // Request five parameters from this component (at maximum)
            QList<int> * paramList = transmissionMissingPackets.value(component, NULL);
            if (paramList)
            {
                int count = 0;
lm's avatar
lm committed
609
                int maxCount = 1;
610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633
                foreach (int id, *paramList)
                {
                    if (count < maxCount)
                    {
                        qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << id << "FROM COMPONENT #" << component;
                        emit requestParameter(component, id);
                        statusLabel->setText(tr("Requ. retransmission of #%1").arg(id));
                        count++;
                    }
                    else
                    {
                        break;
                    }
                }
            }
        }
    }
    else
    {
        qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY";
        setRetransmissionGuardEnabled(false);
    }
}

634

635 636 637 638 639 640 641
/**
 * @param component the subsystem which has the parameter
 * @param parameterName name of the parameter, as delivered by the system
 * @param value value of the parameter
 */
void QGCParamWidget::setParameter(int component, QString parameterName, float value)
{
642
    emit parameterChanged(component, parameterName, value);
643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659
//    // Wait for parameter to be written back
//    // mark it therefore as missing
//    if (!transmissionMissingPackets.contains(component))
//    {
//        transmissionMissingPackets.insert(component, new QList<int>());
//    }

//    for (int i = 0; i < paramCount; ++i)
//    {
//        if (!transmissionMissingPackets.value(component)->contains(i))
//        {
//            transmissionMissingPackets.value(component)->append(i);
//        }
//    }
//    transmissionActive = true;
//    transmissionStarted = QGC::groundTimeUsecs();
//    setRetransmissionGuardEnabled(true);
660 661
}

662 663 664
/**
 * Set all parameter in the parameter tree on the MAV
 */
665 666
void QGCParamWidget::setParameters()
{
667
    // Iterate through all components, through all parameters and emit them
668
    int parametersSent = 0;
669 670 671 672 673 674 675 676 677 678
    QMap<int, QMap<QString, float>*>::iterator i;
    for (i = changedValues.begin(); i != changedValues.end(); ++i)
    {
        // Iterate through the parameters of the component
        int compid = i.key();
        QMap<QString, float>* comp = i.value();
        {
            QMap<QString, float>::iterator j;
            for (j = comp->begin(); j != comp->end(); ++j)
            {
679
                setParameter(compid, j.key(), j.value());
680
                parametersSent++;
681 682 683 684
            }
        }
    }

685 686 687 688 689 690 691 692 693 694
    // Update stats label
    if (parametersSent == 0)
    {
        statusLabel->setText(tr("No transmission: No changed values."));
    }
    else
    {
        statusLabel->setText(tr("Transmitting %1 parameters.").arg(parametersSent));
    }

lm's avatar
lm committed
695
    changedValues.clear();
696 697
}

698 699 700 701
/**
 * Write the current onboard parameters from RAM into
 * permanent storage, e.g. EEPROM or harddisk
 */
702 703
void QGCParamWidget::writeParameters()
{
704 705 706 707 708 709
    mav->writeParametersToStorage();
}

void QGCParamWidget::readParameters()
{
    mav->readParametersFromStorage();
710 711
}

712 713 714
/**
 * Clear all data in the parameter widget
 */
pixhawk's avatar
pixhawk committed
715 716 717
void QGCParamWidget::clear()
{
    tree->clear();
lm's avatar
lm committed
718
    components->clear();
pixhawk's avatar
pixhawk committed
719
}