WaypointViewOnlyView.cc 7.08 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
#include <QDebug>
#include "WaypointViewOnlyView.h"
#include "ui_WaypointViewOnlyView.h"

WaypointViewOnlyView::WaypointViewOnlyView(Waypoint* wp, QWidget *parent) :
    QWidget(parent),
    m_ui(new Ui::WaypointViewOnlyView)
{
    m_ui->setupUi(this);
    this->wp = wp;
    updateValues();

    connect(m_ui->current, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
    connect(m_ui->autoContinue, SIGNAL(stateChanged(int)),this, SLOT(changedAutoContinue(int)));
}

void WaypointViewOnlyView::changedAutoContinue(int state)
{
    bool new_value = false;
    if (state != 0)
    {
        new_value = true;
    }
    m_ui->autoContinue->blockSignals(true);
    m_ui->autoContinue->setChecked(state);
    m_ui->autoContinue->blockSignals(false);
    wp->setAutocontinue(new_value);
    emit changeAutoContinue(wp->getId(),new_value);
29
}
30 31 32 33

void WaypointViewOnlyView::changedCurrent(int state)
{
    qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId();
34
    m_ui->current->blockSignals(true);
35 36
    if (state == 0)
    {
37 38 39 40 41
        /*

        m_ui->current->setStyleSheet("");

        */
42 43 44 45 46 47 48 49
        if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current
        {
            m_ui->current->setChecked(true);
            m_ui->current->setCheckState(Qt::Checked);
        }
        else
        {
            m_ui->current->setChecked(false);
50
            m_ui->current->setCheckState(Qt::Unchecked);            
51 52 53 54
            wp->setCurrent(false);
        }
    }
    else
55 56 57 58 59 60 61 62 63 64 65 66
    {        
        /*
        FIXME: The checkbox should turn gray to indicate, that set_current request has been sent to UAV. It should become blue (checked) after receiving set_current_ack from waypointplanner.

        m_ui->current->setStyleSheet("*::indicator { \
            border: 1px solid #777777; \
            border-radius: 2px; \
            color: #999999; \
                 width: 10px; \
             height: 10px; \
        }");
        */
67 68 69
        wp->setCurrent(true);
        emit changeCurrentWaypoint(wp->getId());   //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
    }
70
    m_ui->current->blockSignals(false);
71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89
}

void WaypointViewOnlyView::setCurrent(bool state)
{
    m_ui->current->blockSignals(true);
    m_ui->current->setChecked(state);
    m_ui->current->blockSignals(false);
}

void WaypointViewOnlyView::updateValues()
{
    qDebug() << "Trof: WaypointViewOnlyView::updateValues() ID:" << wp->getId();
    // Check if we just lost the wp, delete the widget
    // accordingly
    if (!wp)
    {
        deleteLater();
        return;
    }
90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124

    // Update style

    QColor backGroundColor = QGC::colorBackground;

    static int lastId = -1;
    int currId = wp->getId() % 2;

    if (currId != lastId)
    {

        // qDebug() << "COLOR ID: " << currId;
        if (currId == 1)
        {
            backGroundColor = QColor("#252528").lighter(150);
        }
        else
        {
            backGroundColor = QColor("#252528").lighter(250);
        }

        // Update color based on id
        QString groupBoxStyle = QString("QGroupBox {padding: 0px; margin: 0px; border: 0px; background-color: %1; min-height: 12px; }").arg(backGroundColor.name());
        QString labelStyle = QString("QWidget {background-color: %1; color: #DDDDDF; border-color: #EEEEEE; }").arg(backGroundColor.name());
        QString displayBarStyle = QString("QWidget {background-color: %1; color: #DDDDDF; border: none; }").arg(backGroundColor.name());
        QString checkBoxStyle = QString("QCheckBox {background-color: %1; color: #454545; border-color: #EEEEEE; }").arg(backGroundColor.name());

        m_ui->autoContinue->setStyleSheet(checkBoxStyle);
        m_ui->current->setStyleSheet(checkBoxStyle);
        m_ui->idLabel->setStyleSheet(labelStyle);
        m_ui->displayBar->setStyleSheet(displayBarStyle);
        m_ui->groupBox->setStyleSheet(groupBoxStyle);
        lastId = currId;
    }

125 126 127 128 129 130
    // update frame

    m_ui->idLabel->setText(QString("%1").arg(wp->getId()));

    if (m_ui->current->isChecked() != wp->getCurrent())
    {
131
        m_ui->current->blockSignals(true);
132
        m_ui->current->setChecked(wp->getCurrent());
133
        m_ui->current->blockSignals(false);
134 135 136
    }
    if (m_ui->autoContinue->isChecked() != wp->getAutoContinue())
    {
137
        m_ui->autoContinue->blockSignals(true);
138
        m_ui->autoContinue->setChecked(wp->getAutoContinue());
139
        m_ui->autoContinue->blockSignals(false);
140 141
    }

142 143 144
    switch (wp->getAction())
    {
    case MAV_CMD_NAV_WAYPOINT:
145 146 147
    {
        if (wp->getParam1()>0)
        {
lm's avatar
lm committed
148
            m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
149 150 151
        }
        else
        {
lm's avatar
lm committed
152
            m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b>; yaw: %4; rad: %5").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4()).arg(wp->getParam2()));
153 154 155
        }
        break;
    }
156
    case MAV_CMD_NAV_LAND:
157 158 159 160
    {
        m_ui->displayBar->setText(QString("LAND. Go to (%1, %2, %3) and descent; yaw: %4").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4()));
        break;
    }
161
    case MAV_CMD_NAV_TAKEOFF:
162 163 164 165
    {
        m_ui->displayBar->setText(QString("TAKEOFF. Go to (%1, %2, %3); yaw: %4").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4()));
        break;
    }
166
    case MAV_CMD_DO_JUMP:
167 168 169 170 171 172 173 174 175 176 177
    {
        if (wp->getParam2()>0)
        {
            m_ui->displayBar->setText(QString("Jump to waypoint %1. Jumps left: %2").arg(wp->getParam1()).arg(wp->getParam2()));
        }
        else
        {
            m_ui->displayBar->setText(QString("No jumps left. Proceed to next waypoint."));
        }
        break;
    }
178
    case MAV_CMD_CONDITION_DELAY:
179 180 181 182
    {
        m_ui->displayBar->setText(QString("Delay: %1 sec").arg(wp->getParam1()));
        break;
    }
183
    case 237: //MAV_CMD_DO_START_SEARCH
184 185 186 187
    {
        m_ui->displayBar->setText(QString("Start searching for pattern. Success when got more than %2 detections with confidence %1").arg(wp->getParam1()).arg(wp->getParam2()));
        break;
    }
188
    case 238: //MAV_CMD_DO_FINISH_SEARCH
189 190 191 192
    {
        m_ui->displayBar->setText(QString("Check if search was successful. yes -> jump to %1, no -> jump to %2.  Jumps left: %3").arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()));
        break;
    }
193
    case 240: //MAV_CMD_DO_SWEEP
194 195 196 197
    {
        m_ui->displayBar->setText(QString("Sweep. Corners: (%1,%2) and (%3,%4); z: %5; scan radius: %6").arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7()).arg(wp->getParam1()));
        break;
    }
198
    default:
199 200 201 202
    {
        m_ui->displayBar->setText(QString("Unknown Command ID (%1) : %2, %3, %4, %5, %6, %7, %8").arg(wp->getAction()).arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7()));
        break;
    }
203
    }
204 205 206 207 208 209
}

WaypointViewOnlyView::~WaypointViewOnlyView()
{
    delete m_ui;
}