QGCMapRCToParamDialog.h 2.44 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32
/*=====================================================================

 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>
33

34
#include "UASInterface.h"
35
#include "AutoPilotPlugin.h"
36 37 38 39 40 41 42 43 44 45 46

namespace Ui {
class QGCMapRCToParamDialog;
}


class ParamLoader : public QObject
{
    Q_OBJECT

public:
47
    ParamLoader(QString paramName, UASInterface* uas, QObject* parent = NULL);
48 49 50 51 52 53 54

public slots:
    void load();

signals:
    void paramLoaded(bool success, float value, QString message = "");
    void correctParameterChanged();
55 56 57
    
private slots:
    void _parameterUpdated(QVariant value);
58

59 60 61 62 63
private:
    UASInterface*       _uas;
    AutoPilotPlugin*    _autopilot;
    QString             _paramName;
    bool                _paramReceived;
64 65 66 67 68 69 70 71 72 73 74 75 76
};

class QGCMapRCToParamDialog : public QDialog
{
    Q_OBJECT
    QThread paramLoadThread;

public:
    explicit QGCMapRCToParamDialog(QString param_id,
            UASInterface *mav, QWidget *parent = 0);
    ~QGCMapRCToParamDialog();

signals:
77 78
    void mapRCToParamDialogResult(QString param_id, float scale, float value0,
            quint8 param_rc_channel_index, float valueMin, float valueMax);
79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94
    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