WaypointView.cc 18.6 KB
Newer Older
pixhawk's avatar
pixhawk committed
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5 6 7 8 9
======================================================================*/

/**
 * @file
 *   @brief Displays one waypoint
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *   @author Benjamin Knecht <mavteam@student.ethz.ch>
10
 *   @author Petri Tanskanen <mavteam@student.ethz.ch>
pixhawk's avatar
pixhawk committed
11 12 13 14 15 16
 *
 */

#include <QDoubleSpinBox>
#include <QDebug>

17 18
#include <cmath>
#include <qmath.h>
pixhawk's avatar
pixhawk committed
19

pixhawk's avatar
pixhawk committed
20 21
#include "WaypointView.h"
#include "ui_WaypointView.h"
22
#include "ui_QGCCustomWaypointAction.h"
pixhawk's avatar
pixhawk committed
23 24

WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
pixhawk's avatar
pixhawk committed
25
        QWidget(parent),
26
        customCommand(new Ui_QGCCustomWaypointAction),
27
        viewMode(QGC_WAYPOINTVIEW_MODE_NAV),
pixhawk's avatar
pixhawk committed
28
        m_ui(new Ui::WaypointView)
pixhawk's avatar
pixhawk committed
29 30 31 32
{
    m_ui->setupUi(this);

    this->wp = wp;
pixhawk's avatar
pixhawk committed
33
    connect(wp, SIGNAL(destroyed(QObject*)), this, SLOT(deleted(QObject*)));
34

35 36 37
    // CUSTOM COMMAND WIDGET
    customCommand->setupUi(m_ui->customActionWidget);

38
    // add actions
39 40 41 42 43 44 45
    m_ui->comboBox_action->addItem(tr("NAV: Waypoint"),MAV_CMD_NAV_WAYPOINT);
    m_ui->comboBox_action->addItem(tr("NAV: TakeOff"),MAV_CMD_NAV_TAKEOFF);
    m_ui->comboBox_action->addItem(tr("NAV: Loiter Unlim."),MAV_CMD_NAV_LOITER_UNLIM);
    m_ui->comboBox_action->addItem(tr("NAV: Loiter Time"),MAV_CMD_NAV_LOITER_TIME);
    m_ui->comboBox_action->addItem(tr("NAV: Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
    m_ui->comboBox_action->addItem(tr("NAV: Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
    m_ui->comboBox_action->addItem(tr("NAV: Land"),MAV_CMD_NAV_LAND);
lm's avatar
lm committed
46 47 48 49
//    m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
    //m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
    //m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
    //m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
50
    m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
51 52 53 54

    // add frames 
    m_ui->comboBox_frame->addItem("Global",MAV_FRAME_GLOBAL);
    m_ui->comboBox_frame->addItem("Local",MAV_FRAME_LOCAL);
55 56 57 58 59
    m_ui->comboBox_frame->addItem("Mission",MAV_FRAME_MISSION);

    // Initialize view correctly
    updateActionView(wp->getAction());
    updateFrameView(wp->getFrame());
60

pixhawk's avatar
pixhawk committed
61
    // Read values and set user interface
62
    updateValues();
pixhawk's avatar
pixhawk committed
63

64 65 66 67 68 69
    // Check for mission frame
    if (wp->getFrame() == MAV_FRAME_MISSION)
    {
        m_ui->comboBox_action->setCurrentIndex(m_ui->comboBox_action->count()-1);
    }

70 71 72 73
    connect(m_ui->posNSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
    connect(m_ui->posESpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
    connect(m_ui->posDSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));

74 75
    connect(m_ui->latSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
    connect(m_ui->lonSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
76
    connect(m_ui->altSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
lm's avatar
lm committed
77
    connect(m_ui->yawSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setYaw(int)));
pixhawk's avatar
pixhawk committed
78 79 80 81 82

    connect(m_ui->upButton, SIGNAL(clicked()), this, SLOT(moveUp()));
    connect(m_ui->downButton, SIGNAL(clicked()), this, SLOT(moveDown()));
    connect(m_ui->removeButton, SIGNAL(clicked()), this, SLOT(remove()));

pixhawk's avatar
pixhawk committed
83 84
    connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int)));
    connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
85 86
    connect(m_ui->comboBox_action, SIGNAL(activated(int)), this, SLOT(changedAction(int)));
    connect(m_ui->comboBox_frame, SIGNAL(activated(int)), this, SLOT(changedFrame(int)));
pixhawk's avatar
pixhawk committed
87

88 89
    connect(m_ui->orbitSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setLoiterOrbit(double)));
    connect(m_ui->acceptanceSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setAcceptanceRadius(double)));
lm's avatar
lm committed
90
    connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setHoldTime(double)));
91
    connect(m_ui->turnsSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setTurns(int)));
92
    connect(m_ui->takeOffAngleSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
93 94 95 96 97 98 99

    // Connect actions
    connect(customCommand->commandSpinBox, SIGNAL(valueChanged(int)),   wp, SLOT(setAction(int)));
    connect(customCommand->param1SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
    connect(customCommand->param2SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam2(double)));
    connect(customCommand->param3SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam3(double)));
    connect(customCommand->param4SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam4(double)));
100 101
    connect(customCommand->param5SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam5(double)));
    connect(customCommand->param6SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam6(double)));
lm's avatar
lm committed
102
    connect(customCommand->param7SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam7(double)));
pixhawk's avatar
pixhawk committed
103 104
}

pixhawk's avatar
pixhawk committed
105 106 107 108 109 110 111 112 113 114 115 116 117
void WaypointView::moveUp()
{
    emit moveUpWaypoint(wp);
}

void WaypointView::moveDown()
{
    emit moveDownWaypoint(wp);
}

void WaypointView::remove()
{
    emit removeWaypoint(wp);
118
    deleteLater();
pixhawk's avatar
pixhawk committed
119 120
}

pixhawk's avatar
pixhawk committed
121
void WaypointView::changedAutoContinue(int state)
pixhawk's avatar
pixhawk committed
122 123
{
    if (state == 0)
124
        wp->setAutocontinue(false);
pixhawk's avatar
pixhawk committed
125
    else
126
        wp->setAutocontinue(true);
pixhawk's avatar
pixhawk committed
127 128
}

129
void WaypointView::updateActionView(int action)
130 131
{
    // expose ui based on action
132

133 134
    switch(action)
    {
135
    case MAV_CMD_NAV_TAKEOFF:
136 137 138 139 140 141 142
        m_ui->orbitSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->autoContinue->hide();
        m_ui->holdTimeSpinBox->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->customActionWidget->hide();
143 144
        m_ui->takeOffAngleSpinBox->show();
        break;
145
    case MAV_CMD_NAV_LAND:
146 147 148 149 150 151 152 153 154
        m_ui->orbitSpinBox->hide();
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->autoContinue->hide();
        m_ui->holdTimeSpinBox->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->customActionWidget->hide();
        break;
155
    case MAV_CMD_NAV_RETURN_TO_LAUNCH:
156 157 158 159 160 161 162 163
        m_ui->orbitSpinBox->hide();
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->autoContinue->hide();
        m_ui->holdTimeSpinBox->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->customActionWidget->hide();
164
        break;
165
    case MAV_CMD_NAV_WAYPOINT:
166 167 168
        m_ui->orbitSpinBox->hide();
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->turnsSpinBox->hide();
lm's avatar
lm committed
169
        m_ui->holdTimeSpinBox->show();
170 171
        m_ui->customActionWidget->hide();

172
        m_ui->autoContinue->show();
173 174
        m_ui->acceptanceSpinBox->show();
        m_ui->yawSpinBox->show();
175
        break;
176
    case MAV_CMD_NAV_LOITER_UNLIM:
177 178 179 180 181 182 183 184 185
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->autoContinue->hide();
        m_ui->holdTimeSpinBox->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->customActionWidget->hide();
        m_ui->orbitSpinBox->show();
        break;
186
    case MAV_CMD_NAV_LOITER_TURNS:
187 188 189 190 191 192 193 194 195
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->autoContinue->hide();
        m_ui->holdTimeSpinBox->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->customActionWidget->hide();
        m_ui->orbitSpinBox->show();
        m_ui->turnsSpinBox->show();
        break;
196
    case MAV_CMD_NAV_LOITER_TIME:
197 198 199 200 201 202
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->autoContinue->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->customActionWidget->hide();
203 204 205
        m_ui->orbitSpinBox->show();
        m_ui->holdTimeSpinBox->show();
        break;
206 207 208 209 210 211 212 213 214 215 216
    case MAV_CMD_NAV_TARGET:
        m_ui->orbitSpinBox->hide();
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->holdTimeSpinBox->show();
        m_ui->customActionWidget->hide();

        m_ui->autoContinue->show();
        m_ui->acceptanceSpinBox->hide();
        m_ui->yawSpinBox->hide();
        break;
217
    default:
218
        break;
219 220 221
    }
}

222 223 224 225
/**
 * @param index The index of the combo box of the action entry, NOT the action ID
 */
void WaypointView::changedAction(int index)
226 227
{
    // set waypoint action
228
    int actionIndex = m_ui->comboBox_action->itemData(index).toUInt();
229
    if (actionIndex < MAV_CMD_ENUM_END && actionIndex >= 0)
230
    {
231
        MAV_CMD action = (MAV_CMD) actionIndex;
232 233 234 235 236 237 238 239 240
        wp->setAction(action);
    }

    // Expose ui based on action
    // Change to mission frame
    // if action is unknown

    switch(actionIndex)
    {
241 242 243 244 245 246 247
    case MAV_CMD_NAV_TAKEOFF:
    case MAV_CMD_NAV_LAND:
    case MAV_CMD_NAV_RETURN_TO_LAUNCH:
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_NAV_LOITER_UNLIM:
    case MAV_CMD_NAV_LOITER_TURNS:
    case MAV_CMD_NAV_LOITER_TIME:
248 249 250
        changeViewMode(QGC_WAYPOINTVIEW_MODE_NAV);
        // Update frame view
        updateFrameView(m_ui->comboBox_frame->currentIndex());
251 252
        // Update view
        updateActionView(actionIndex);
253
        break;
254
    case MAV_CMD_ENUM_END:
255 256
    default:
        // Switch to mission frame
257
        changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING);
258 259 260
        break;
    }
}
261

262
void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
263
{
lm's avatar
lm committed
264
    viewMode = mode;
265
    switch (mode)
266
    {
267
    case QGC_WAYPOINTVIEW_MODE_NAV:
268 269 270 271
    case QGC_WAYPOINTVIEW_MODE_CONDITION:
        // Hide everything, show condition widget
        // TODO
    case QGC_WAYPOINTVIEW_MODE_DO:
272

273
        break;
274
    case QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING:
275 276 277 278 279 280 281 282 283 284 285 286 287 288
        // Hide almost everything
        m_ui->orbitSpinBox->hide();
        m_ui->takeOffAngleSpinBox->hide();
        m_ui->yawSpinBox->hide();
        m_ui->turnsSpinBox->hide();
        m_ui->holdTimeSpinBox->hide();
        m_ui->acceptanceSpinBox->hide();
        m_ui->posDSpinBox->hide();
        m_ui->posESpinBox->hide();
        m_ui->posNSpinBox->hide();
        m_ui->latSpinBox->hide();
        m_ui->lonSpinBox->hide();
        m_ui->altSpinBox->hide();

lm's avatar
lm committed
289 290 291
        int action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
        m_ui->comboBox_action->setCurrentIndex(action_index);

292 293 294 295 296 297 298 299 300
        // Show action widget
        if (!m_ui->customActionWidget->isVisible())
        {
            m_ui->customActionWidget->show();
        }
        if (!m_ui->autoContinue->isVisible())
        {
            m_ui->autoContinue->show();
        }
301
        break;
302
    }
lm's avatar
lm committed
303

304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331
}

void WaypointView::updateFrameView(int frame)
{
    switch(frame)
    {
    case MAV_FRAME_GLOBAL:
        m_ui->posNSpinBox->hide();
        m_ui->posESpinBox->hide();
        m_ui->posDSpinBox->hide();
        m_ui->lonSpinBox->show();
        m_ui->latSpinBox->show();
        m_ui->altSpinBox->show();
        // Coordinate frame
        m_ui->comboBox_frame->show();
        m_ui->customActionWidget->hide();
        break;
    case MAV_FRAME_LOCAL:
        m_ui->lonSpinBox->hide();
        m_ui->latSpinBox->hide();
        m_ui->altSpinBox->hide();
        m_ui->posNSpinBox->show();
        m_ui->posESpinBox->show();
        m_ui->posDSpinBox->show();
        // Coordinate frame
        m_ui->comboBox_frame->show();
        m_ui->customActionWidget->hide();
        break;
332 333 334 335 336
    default:
        std::cerr << "unknown frame" << std::endl;
    }
}

pixhawk's avatar
pixhawk committed
337 338
void WaypointView::deleted(QObject* waypoint)
{
339
    Q_UNUSED(waypoint);
lm's avatar
lm committed
340 341 342 343
//    if (waypoint == this->wp)
//    {
//        deleteLater();
//    }
pixhawk's avatar
pixhawk committed
344 345
}

346 347 348 349 350 351 352 353 354
void WaypointView::changedFrame(int index)
{
    // set waypoint action
    MAV_FRAME frame = (MAV_FRAME)m_ui->comboBox_frame->itemData(index).toUInt();
    wp->setFrame(frame);

    updateFrameView(frame);
}

pixhawk's avatar
pixhawk committed
355
void WaypointView::changedCurrent(int state)
pixhawk's avatar
pixhawk committed
356
{
pixhawk's avatar
pixhawk committed
357 358
    if (state == 0)
    {
pixhawk's avatar
pixhawk committed
359 360 361
        m_ui->selectedBox->setChecked(true);
        m_ui->selectedBox->setCheckState(Qt::Checked);
        wp->setCurrent(false);
pixhawk's avatar
pixhawk committed
362 363 364
    }
    else
    {
pixhawk's avatar
pixhawk committed
365
        wp->setCurrent(true);
366
        emit changeCurrentWaypoint(wp->getId());   //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
pixhawk's avatar
pixhawk committed
367
    }
pixhawk's avatar
pixhawk committed
368 369
}

370 371
void WaypointView::updateValues()
{
pixhawk's avatar
pixhawk committed
372 373 374 375 376 377 378
    // Check if we just lost the wp, delete the widget
    // accordingly
    if (!wp)
    {
        deleteLater();
        return;
    }
379 380
    // Deactivate signals from the WP
    wp->blockSignals(true);
381 382
    // update frame
    MAV_FRAME frame = wp->getFrame();
383
    int frame_index = m_ui->comboBox_frame->findData(frame);
384 385 386
    if (m_ui->comboBox_frame->currentIndex() != frame_index)
    {
        m_ui->comboBox_frame->setCurrentIndex(frame_index);
387
        updateFrameView(frame);
388
    }
389 390 391
    switch(frame)
    {
    case(MAV_FRAME_LOCAL):
pixhawk's avatar
pixhawk committed
392 393 394 395 396 397 398 399 400 401 402 403 404 405
        {
            if (m_ui->posNSpinBox->value() != wp->getX())
            {
                m_ui->posNSpinBox->setValue(wp->getX());
            }
            if (m_ui->posESpinBox->value() != wp->getY())
            {
                m_ui->posESpinBox->setValue(wp->getY());
            }
            if (m_ui->posDSpinBox->value() != wp->getZ())
            {
                m_ui->posDSpinBox->setValue(wp->getZ());
            }
        }
406 407
        break;
    case(MAV_FRAME_GLOBAL):
pixhawk's avatar
pixhawk committed
408
        {
409
            if (m_ui->latSpinBox->value() != wp->getX())
pixhawk's avatar
pixhawk committed
410
            {
411
                m_ui->latSpinBox->setValue(wp->getX());
pixhawk's avatar
pixhawk committed
412
            }
413
            if (m_ui->lonSpinBox->value() != wp->getY())
pixhawk's avatar
pixhawk committed
414
            {
415
                m_ui->lonSpinBox->setValue(wp->getY());
pixhawk's avatar
pixhawk committed
416 417 418 419 420 421
            }
            if (m_ui->altSpinBox->value() != wp->getZ())
            {
                m_ui->altSpinBox->setValue(wp->getZ());
            }
        }
422
        break;
423 424
    default:
        // Do nothing
425
        break;
426 427
    }

428
    // Update action
429
    MAV_CMD action = wp->getAction();
430
    int action_index = m_ui->comboBox_action->findData(action);
431 432 433
    // Set to "Other" action if it was -1
    if (action_index == -1)
    {
434
        action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
435 436
    }
    // Only update if changed
pixhawk's avatar
pixhawk committed
437 438
    if (m_ui->comboBox_action->currentIndex() != action_index)
    {
439 440
        // If action is unknown, set direct editing mode
        if (wp->getAction() < 0 || wp->getAction() > MAV_CMD_NAV_TAKEOFF)
441
        {
442 443 444 445
            changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING);
        }
        else
        {
lm's avatar
lm committed
446 447 448 449 450 451
            if (viewMode != QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING)
            {
                // Action ID known, update
                m_ui->comboBox_action->setCurrentIndex(action_index);
                updateActionView(action);
            }
452
        }
pixhawk's avatar
pixhawk committed
453
    }
454 455
    switch(action)
    {
456
    case MAV_CMD_NAV_TAKEOFF:
457
        break;
458
    case MAV_CMD_NAV_LAND:
459
        break;
460
    case MAV_CMD_NAV_WAYPOINT:
461
        break;
462
    case MAV_CMD_NAV_LOITER_UNLIM:
463 464 465 466 467
        break;
    default:
        std::cerr << "unknown action" << std::endl;
    }

lm's avatar
lm committed
468
    if (m_ui->yawSpinBox->value() != wp->getYaw())
pixhawk's avatar
pixhawk committed
469
    {
lm's avatar
lm committed
470
        if (!m_ui->yawSpinBox->isVisible()) m_ui->yawSpinBox->blockSignals(true);
lm's avatar
lm committed
471
        m_ui->yawSpinBox->setValue(wp->getYaw());
lm's avatar
lm committed
472
        if (!m_ui->yawSpinBox->isVisible()) m_ui->yawSpinBox->blockSignals(false);
pixhawk's avatar
pixhawk committed
473
    }
pixhawk's avatar
pixhawk committed
474 475 476 477 478 479 480 481
    if (m_ui->selectedBox->isChecked() != wp->getCurrent())
    {
        m_ui->selectedBox->setChecked(wp->getCurrent());
    }
    if (m_ui->autoContinue->isChecked() != wp->getAutoContinue())
    {
        m_ui->autoContinue->setChecked(wp->getAutoContinue());
    }
pixhawk's avatar
pixhawk committed
482
    m_ui->idLabel->setText(QString("%1").arg(wp->getId()));
483
    if (m_ui->orbitSpinBox->value() != wp->getLoiterOrbit())
pixhawk's avatar
pixhawk committed
484
    {
lm's avatar
lm committed
485
        if (!m_ui->orbitSpinBox->isVisible()) m_ui->orbitSpinBox->blockSignals(true);
486
        m_ui->orbitSpinBox->setValue(wp->getLoiterOrbit());
lm's avatar
lm committed
487
        if (!m_ui->orbitSpinBox->isVisible()) m_ui->orbitSpinBox->blockSignals(false);
488 489 490
    }
    if (m_ui->acceptanceSpinBox->value() != wp->getAcceptanceRadius())
    {
lm's avatar
lm committed
491
        if (!m_ui->acceptanceSpinBox->isVisible()) m_ui->acceptanceSpinBox->blockSignals(true);
492
        m_ui->acceptanceSpinBox->setValue(wp->getAcceptanceRadius());
lm's avatar
lm committed
493
        if (!m_ui->acceptanceSpinBox->isVisible()) m_ui->acceptanceSpinBox->blockSignals(false);
pixhawk's avatar
pixhawk committed
494 495 496
    }
    if (m_ui->holdTimeSpinBox->value() != wp->getHoldTime())
    {
lm's avatar
lm committed
497
        if (!m_ui->holdTimeSpinBox->isVisible()) m_ui->holdTimeSpinBox->blockSignals(true);
pixhawk's avatar
pixhawk committed
498
        m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
lm's avatar
lm committed
499
        if (!m_ui->holdTimeSpinBox->isVisible()) m_ui->holdTimeSpinBox->blockSignals(false);
pixhawk's avatar
pixhawk committed
500
    }
501 502
    if (m_ui->turnsSpinBox->value() != wp->getTurns())
    {
lm's avatar
lm committed
503
        if (!m_ui->turnsSpinBox->isVisible()) m_ui->turnsSpinBox->blockSignals(true);
504
        m_ui->turnsSpinBox->setValue(wp->getTurns());
lm's avatar
lm committed
505
        if (!m_ui->turnsSpinBox->isVisible()) m_ui->turnsSpinBox->blockSignals(false);
506 507 508
    }
    if (m_ui->takeOffAngleSpinBox->value() != wp->getParam1())
    {
lm's avatar
lm committed
509
        if (!m_ui->takeOffAngleSpinBox->isVisible()) m_ui->takeOffAngleSpinBox->blockSignals(true);
510
        m_ui->takeOffAngleSpinBox->setValue(wp->getParam1());
lm's avatar
lm committed
511
        if (!m_ui->takeOffAngleSpinBox->isVisible()) m_ui->takeOffAngleSpinBox->blockSignals(false);
512
    }
513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540

    // UPDATE CUSTOM ACTION WIDGET

    if (customCommand->commandSpinBox->value() != wp->getAction())
    {
        customCommand->commandSpinBox->setValue(wp->getAction());
        qDebug() << "Changed action";
    }
    // Param 1
    if (customCommand->param1SpinBox->value() != wp->getParam1())
    {
        customCommand->param1SpinBox->setValue(wp->getParam1());
    }
    // Param 2
    if (customCommand->param2SpinBox->value() != wp->getParam2())
    {
        customCommand->param2SpinBox->setValue(wp->getParam2());
    }
    // Param 3
    if (customCommand->param3SpinBox->value() != wp->getParam3())
    {
        customCommand->param3SpinBox->setValue(wp->getParam3());
    }
    // Param 4
    if (customCommand->param4SpinBox->value() != wp->getParam4())
    {
        customCommand->param4SpinBox->setValue(wp->getParam4());
    }
541 542 543 544 545 546 547 548 549 550
    // Param 5
    if (customCommand->param5SpinBox->value() != wp->getParam5())
    {
        customCommand->param5SpinBox->setValue(wp->getParam5());
    }
    // Param 6
    if (customCommand->param6SpinBox->value() != wp->getParam6())
    {
        customCommand->param6SpinBox->setValue(wp->getParam6());
    }
lm's avatar
lm committed
551 552 553 554 555
    // Param 7
    if (customCommand->param7SpinBox->value() != wp->getParam7())
    {
        customCommand->param7SpinBox->setValue(wp->getParam7());
    }
556

557
    wp->blockSignals(false);
558 559
}

pixhawk's avatar
pixhawk committed
560
void WaypointView::setCurrent(bool state)
pixhawk's avatar
pixhawk committed
561
{
562
    m_ui->selectedBox->blockSignals(true);
563
    m_ui->selectedBox->setChecked(state);
564
    m_ui->selectedBox->blockSignals(false);
pixhawk's avatar
pixhawk committed
565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581
}

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

void WaypointView::changeEvent(QEvent *e)
{
    switch (e->type()) {
    case QEvent::LanguageChange:
        m_ui->retranslateUi(this);
        break;
    default:
        break;
    }
}