Pixhawk3DWidget.cc 74.2 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
///*=====================================================================
//
//QGroundControl Open Source Ground Control Station
//
//(c) 2009, 2010 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 Definition of the class Pixhawk3DWidget.
 *
28
 *   @author Lionel Heng <hengli@inf.ethz.ch>
29 30 31 32 33 34 35 36
 *
 */

#include "Pixhawk3DWidget.h"

#include <sstream>

#include <osg/Geode>
37
#include <osg/Image>
38
#include <osgDB/ReadFile>
39 40
#include <osg/LineWidth>
#include <osg/ShapeDrawable>
41
#include <osgText/Text>
42

43
#include "../MainWindow.h"
44
#include "PixhawkCheetahNode.h"
45
#include "TerrainParamDialog.h"
46
#include "UASManager.h"
Don Gagne's avatar
Don Gagne committed
47
#include "QGCFileDialog.h"
Don Gagne's avatar
Don Gagne committed
48
#include "QGCMessageBox.h"
49

50
#include "QGC.h"
51
#include "gpl.h"
52 53

Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
54 55 56 57 58 59 60 61 62 63
 : kMessageTimeout(4.0)
 , mMode(DEFAULT_MODE)
 , mSelectedWpIndex(-1)
 , mActiveSystemId(-1)
 , mActiveUAS(NULL)
 , mGlobalViewParams(new GlobalViewParams)
 , mFollowCameraId(-1)
 , mInitCameraPos(false)
 , m3DWidget(new Q3DWidget(this))
 , mViewParamWidget(new ViewParamWidget(mGlobalViewParams, mSystemViewParamMap, this, parent))
64
{
65
    connect(m3DWidget, SIGNAL(sizeChanged(int,int)), this, SLOT(sizeChanged(int,int)));
66
    connect(m3DWidget, SIGNAL(updateWidget()), this, SLOT(updateWidget()));
67

68 69 70
    m3DWidget->setCameraParams(2.0f, 30.0f, 0.01f, 10000.0f);
    m3DWidget->init(15.0f);
    m3DWidget->handleDeviceEvents() = false;
71

72 73
    mWorldGridNode = createWorldGrid();
    m3DWidget->worldMap()->addChild(mWorldGridNode, false);
74

75 76 77
    mTerrainPAT = new osg::PositionAttitudeTransform;
    m3DWidget->worldMap()->addChild(mTerrainPAT);

78
    // generate map model
79
    mImageryNode = createImagery();
80
    mImageryNode->setName("imagery");
81
    m3DWidget->worldMap()->addChild(mImageryNode, false);
82

83
    setupHUD();
84

85
    buildLayout();
86

87 88 89 90 91 92
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
            this, SLOT(activeSystemChanged(UASInterface*)));
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
            this, SLOT(systemCreated(UASInterface*)));
    connect(mGlobalViewParams.data(), SIGNAL(followCameraChanged(int)),
            this, SLOT(followCameraChanged(int)));
93 94
    connect(mGlobalViewParams.data(), SIGNAL(imageryParamsChanged(void)),
            this, SLOT(imageryParamsChanged(void)));
95

96 97
    MainWindow* parentWindow = qobject_cast<MainWindow*>(parent);
    parentWindow->addDockWidget(Qt::LeftDockWidgetArea, mViewParamWidget);
98

99
    mViewParamWidget->hide();
100

101 102 103
    setFocusPolicy(Qt::StrongFocus);
    setMouseTracking(true);
}
104

105 106
Pixhawk3DWidget::~Pixhawk3DWidget()
{
107

108 109
}

110 111
void
Pixhawk3DWidget::activeSystemChanged(UASInterface* uas)
112
{
113 114 115 116
    if (uas)
    {
        mActiveSystemId = uas->getUASID();
    }
117 118

    mActiveUAS = uas;
119

120
    mMode = DEFAULT_MODE;
121 122
}

123
void
124
Pixhawk3DWidget::systemCreated(UASInterface *uas)
125
{
126 127 128
    int systemId = uas->getUASID();

    if (mSystemContainerMap.contains(systemId))
129 130 131 132
    {
        return;
    }

133 134
    mSystemViewParamMap.insert(systemId, SystemViewParamsPtr(new SystemViewParams(systemId)));
    mSystemContainerMap.insert(systemId, SystemContainer());
135

136 137
    connect(uas, SIGNAL(localPositionChanged(UASInterface*,int,double,double,double,quint64)),
            this, SLOT(localPositionChanged(UASInterface*,int,double,double,double,quint64)));
138 139
    connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)),
            this, SLOT(localPositionChanged(UASInterface*,double,double,double,quint64)));
140 141
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)),
            this, SLOT(attitudeChanged(UASInterface*,int,double,double,double,quint64)));
142 143 144 145
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)),
            this, SLOT(attitudeChanged(UASInterface*,double,double,double,quint64)));
    connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)),
            this, SLOT(setpointChanged(int,float,float,float,float)));
146 147
    connect(uas, SIGNAL(homePositionChanged(int,double,double,double)),
            this, SLOT(homePositionChanged(int,double,double,double)));
148

149
//    mSystemContainerMap[systemId].gpsLocalOrigin() = QVector3D(47.397786, 8.544476, 428);
150
    initializeSystem(systemId, uas->getColor());
151

152
    emit systemCreatedSignal(uas);
153 154
}

155
void
156 157 158
Pixhawk3DWidget::localPositionChanged(UASInterface* uas, int component,
                                      double x, double y, double z,
                                      quint64 time)
159
{
160 161
    Q_UNUSED(time);

162 163 164
    int systemId = uas->getUASID();

    if (!mSystemContainerMap.contains(systemId))
165 166 167 168
    {
        return;
    }

169 170 171 172
    SystemContainer& systemData = mSystemContainerMap[systemId];

    // update trail data
    if (!systemData.trailMap().contains(component))
173
    {
174 175 176 177
        systemData.trailMap().insert(component, QVector<osg::Vec3d>());
        systemData.trailMap()[component].reserve(10000);
        systemData.trailIndexMap().insert(component,
                                          systemData.trailMap().size() - 1);
178

hengli's avatar
hengli committed
179 180 181 182 183 184 185 186 187 188 189 190 191 192 193
        // generate nice bright random color
        float golden_ratio_conjugate = 0.618033988749895f;

        float h = (float)qrand() / RAND_MAX + golden_ratio_conjugate;
        if (h > 1.0f)
        {
            h -= 1.0f;
        }

        QColor colorHSV;
        colorHSV.setHsvF(h, 0.99, 0.99, 0.5);

        QColor colorRGB = colorHSV.toRgb();

        osg::Vec4f color(colorRGB.redF(), colorRGB.greenF(), colorRGB.blueF(), colorRGB.alphaF());
194

195
        systemData.trailNode()->addDrawable(createTrail(color));
196
        systemData.trailNode()->addDrawable(createLink(uas->getColor()));
197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237

        double radius = 0.5;

        osg::ref_ptr<osg::Group> group = new osg::Group;

        // cone indicates orientation
        osg::ref_ptr<osg::ShapeDrawable> sd = new osg::ShapeDrawable;
        double coneRadius = radius / 2.0;
        osg::ref_ptr<osg::Cone> cone =
            new osg::Cone(osg::Vec3d(0.0, 0.0, 0.0),
                          coneRadius, radius * 2.0);

        sd->setShape(cone);
        sd->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
        sd->setColor(color);

        osg::ref_ptr<osg::Geode> geode = new osg::Geode;
        geode->addDrawable(sd);

        osg::ref_ptr<osg::PositionAttitudeTransform> pat =
            new osg::PositionAttitudeTransform;
        pat->addChild(geode);
        pat->setAttitude(osg::Quat(- M_PI_2, osg::Vec3d(1.0f, 0.0f, 0.0f),
                                   M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f),
                                   0.0, osg::Vec3d(0.0f, 0.0f, 1.0f)));
        group->addChild(pat);

        // cylinder indicates position
        sd = new osg::ShapeDrawable;
        osg::ref_ptr<osg::Cylinder> cylinder =
            new osg::Cylinder(osg::Vec3d(0.0, 0.0, 0.0),
                              radius, 0);

        sd->setShape(cylinder);
        sd->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
        sd->setColor(color);

        geode = new osg::Geode;
        geode->addDrawable(sd);
        group->addChild(geode);

238
        // text indicates component id
Lorenz Meier's avatar
Lorenz Meier committed
239
        colorRGB = colorRGB.lighter();
240 241
        color = osg::Vec4(colorRGB.redF(), colorRGB.greenF(), colorRGB.blueF(), 1.0f);

242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263
        osg::ref_ptr<osgText::Text> text = new osgText::Text;
        text->setFont(m3DWidget->font());
        text->setText(QString::number(component).toStdString().c_str());
        text->setColor(color);
        text->setCharacterSize(0.3f);
        text->setAxisAlignment(osgText::Text::XY_PLANE);
        text->setAlignment(osgText::Text::CENTER_CENTER);
        text->setPosition(osg::Vec3(0.0, -0.8, 0.0));

        sd = new osg::ShapeDrawable;
        osg::ref_ptr<osg::Box> textBox =
            new osg::Box(osg::Vec3(0.0, -0.8, -0.01), 0.7, 0.4, 0.01);

        sd->setShape(textBox);
        sd->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
        sd->setColor(osg::Vec4(0.0, 0.0, 0.0, 1.0));

        geode = new osg::Geode;
        geode->addDrawable(text);
        geode->addDrawable(sd);
        group->addChild(geode);

264 265 266
        pat = new osg::PositionAttitudeTransform;
        pat->addChild(group);
        systemData.orientationNode()->addChild(pat);
267 268
    }

269
    QVector<osg::Vec3d>& trail = systemData.trailMap()[component];
270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301

    bool addToTrail = false;
    if (trail.size() > 0)
    {
        if (fabs(x - trail[trail.size() - 1].x()) > 0.01f ||
                fabs(y - trail[trail.size() - 1].y()) > 0.01f ||
                fabs(z - trail[trail.size() - 1].z()) > 0.01f)
        {
            addToTrail = true;
        }
    }
    else
    {
        addToTrail = true;
    }

    if (addToTrail)
    {
        osg::Vec3d p(x, y, z);
        if (trail.size() == trail.capacity())
        {
            memcpy(trail.data(), trail.data() + 1,
                   (trail.size() - 1) * sizeof(osg::Vec3d));
            trail[trail.size() - 1] = p;
        }
        else
        {
            trail.append(p);
        }
    }
}

302
void
303 304 305 306
Pixhawk3DWidget::localPositionChanged(UASInterface* uas,
                                      double x, double y, double z,
                                      quint64 time)
{
307 308
    Q_UNUSED(time);

309 310 311 312 313 314 315
    int systemId = uas->getUASID();

    if (!mSystemContainerMap.contains(systemId))
    {
        return;
    }

316 317
//    // Add offset
//    UAS* mav = qobject_cast<UAS*>(uas);
318

319 320 321 322
//    float offX = mav->getNedPosGlobalOffset().x();
//    float offY = mav->getNedPosGlobalOffset().y();
//    float offZ = mav->getNedPosGlobalOffset().z();
//    float offYaw = mav->getNedAttGlobalOffset().z();
323

324 325 326 327
    // update system position
    m3DWidget->systemGroup(systemId)->position()->setPosition(osg::Vec3d(y, x, -z));
}

328 329 330 331 332
void
Pixhawk3DWidget::attitudeChanged(UASInterface* uas, int component,
                                 double roll, double pitch, double yaw,
                                 quint64 time)
{
333 334 335 336
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(time);

337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361
    int systemId = uas->getUASID();

    if (!mSystemContainerMap.contains(systemId))
    {
        return;
    }

    SystemContainer& systemData = mSystemContainerMap[systemId];

    // update trail data
    if (!systemData.trailMap().contains(component))
    {
        return;
    }

    int idx = systemData.trailIndexMap().value(component);

    osg::PositionAttitudeTransform* pat =
        dynamic_cast<osg::PositionAttitudeTransform*>(systemData.orientationNode()->getChild(idx));

    pat->setAttitude(osg::Quat(-yaw, osg::Vec3d(0.0f, 0.0f, 1.0f),
                               0.0, osg::Vec3d(1.0f, 0.0f, 0.0f),
                               0.0, osg::Vec3d(0.0f, 1.0f, 0.0f)));
}

362 363
void
Pixhawk3DWidget::attitudeChanged(UASInterface* uas,
364 365
                                 double roll, double pitch, double yaw,
                                 quint64 time)
366
{
367 368
    Q_UNUSED(time);

369
    int systemId = uas->getUASID();
370

371
    if (!mSystemContainerMap.contains(systemId))
372 373 374 375
    {
        return;
    }

376 377 378 379 380
    // update system attitude
    osg::Quat q(-yaw, osg::Vec3d(0.0f, 0.0f, 1.0f),
                pitch, osg::Vec3d(1.0f, 0.0f, 0.0f),
                roll, osg::Vec3d(0.0f, 1.0f, 0.0f));
    m3DWidget->systemGroup(systemId)->attitude()->setAttitude(q);
381 382
}

383 384 385 386 387 388 389 390 391 392 393 394 395 396
void
Pixhawk3DWidget::homePositionChanged(int uasId, double lat, double lon,
                                     double alt)
{
    if (!mSystemContainerMap.contains(uasId))
    {
        return;
    }

    SystemContainer& systemData = mSystemContainerMap[uasId];

    systemData.gpsLocalOrigin() = QVector3D(lat, lon, alt);
}

397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434
void
Pixhawk3DWidget::setpointChanged(int uasId, float x, float y, float z,
                                 float yaw)
{
    if (!mSystemContainerMap.contains(uasId))
    {
        return;
    }

    UASInterface* uas = UASManager::instance()->getUASForId(uasId);
    if (!uas)
    {
        return;
    }

    QColor color = uas->getColor();
    const SystemViewParamsPtr& systemViewParams = mSystemViewParamMap.value(uasId);

    osg::ref_ptr<osg::PositionAttitudeTransform> pat =
        new osg::PositionAttitudeTransform;

    pat->setPosition(osg::Vec3d(y, x, -z));
    pat->setAttitude(osg::Quat(osg::DegreesToRadians(yaw) - M_PI_2, osg::Vec3d(1.0f, 0.0f, 0.0f),
                               M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f),
                               0.0, osg::Vec3d(0.0f, 0.0f, 1.0f)));

    osg::ref_ptr<osg::Cone> cone = new osg::Cone(osg::Vec3f(0.0f, 0.0f, 0.0f), 0.1f, 0.3f);
    osg::ref_ptr<osg::ShapeDrawable> coneDrawable = new osg::ShapeDrawable(cone);
    coneDrawable->setColor(osg::Vec4f(color.redF(), color.greenF(), color.blueF(), 1.0f));
    coneDrawable->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
    osg::ref_ptr<osg::Geode> coneGeode = new osg::Geode;
    coneGeode->addDrawable(coneDrawable);

    pat->addChild(coneGeode);

    osg::ref_ptr<osg::Group>& setpointGroupNode = mSystemContainerMap[uasId].setpointGroupNode();

    setpointGroupNode->addChild(pat);
435
    if (setpointGroupNode->getNumChildren() > static_cast<unsigned int>(systemViewParams->setpointHistoryLength()))
436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456
    {
        setpointGroupNode->removeChildren(0, setpointGroupNode->getNumChildren() - systemViewParams->setpointHistoryLength());
    }

    osg::Vec4f setpointColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
    int setpointCount = setpointGroupNode->getNumChildren();

    // update colors
    for (int i = 0; i < setpointCount; ++i)
    {
        osg::PositionAttitudeTransform* pat =
            dynamic_cast<osg::PositionAttitudeTransform*>(setpointGroupNode->getChild(i));

        osg::Geode* geode = dynamic_cast<osg::Geode*>(pat->getChild(0));
        osg::ShapeDrawable* sd = dynamic_cast<osg::ShapeDrawable*>(geode->getDrawable(0));

        setpointColor.a() = static_cast<float>(i + 1) / setpointCount;
        sd->setColor(setpointColor);
    }
}

457 458 459 460 461 462 463 464 465 466 467 468 469 470
void
Pixhawk3DWidget::clearData(void)
{
    QMutableMapIterator<int, SystemContainer> it(mSystemContainerMap);
    while (it.hasNext())
    {
        it.next();

        SystemContainer& systemData = it.value();

        // clear setpoint data
        systemData.setpointGroupNode()->removeChildren(0, systemData.setpointGroupNode()->getNumChildren());

        // clear trail data
471 472
        systemData.orientationNode()->removeChildren(0, systemData.orientationNode()->getNumChildren());
        systemData.trailIndexMap().clear();
473
        systemData.trailMap().clear();
474
        systemData.trailNode()->removeDrawables(0, systemData.trailNode()->getNumDrawables());
475 476 477
    }
}

478 479 480 481 482
void
Pixhawk3DWidget::showTerrainParamWindow(void)
{
    TerrainParamDialog::getTerrainParams(mGlobalViewParams);

483 484
    const QVector3D& positionOffset = mGlobalViewParams->terrainPositionOffset();
    const QVector3D& attitudeOffset = mGlobalViewParams->terrainAttitudeOffset();
485

486
    mTerrainPAT->setPosition(osg::Vec3d(positionOffset.y(), positionOffset.x(), -positionOffset.z()));
487
    mTerrainPAT->setAttitude(osg::Quat(- attitudeOffset.z(), osg::Vec3d(0.0f, 0.0f, 1.0f),
488 489
                                       attitudeOffset.y(), osg::Vec3d(1.0f, 0.0f, 0.0f),
                                       attitudeOffset.x(), osg::Vec3d(0.0f, 1.0f, 0.0f)));
490 491
}

492
void
493
Pixhawk3DWidget::showViewParamWindow(void)
494
{
495 496 497 498 499
    if (mViewParamWidget->isVisible())
    {
        mViewParamWidget->hide();
    }
    else
500
    {
501
        mViewParamWidget->show();
502
    }
503 504
}

505
void
506
Pixhawk3DWidget::followCameraChanged(int systemId)
507
{
508
    if (systemId == -1)
509
    {
510
        mFollowCameraId = -1;
511 512
    }

513 514
    UASInterface* uas = UASManager::instance()->getUASForId(systemId);
    if (!uas)
515
    {
516
        return;
517
    }
518 519

    if (mFollowCameraId != systemId)
520
    {
521 522 523 524 525 526 527 528
        double x = 0.0, y = 0.0, z = 0.0;
        getPosition(uas, mGlobalViewParams->frame(), x, y, z);

        mCameraPos = QVector3D(x, y, z);

        m3DWidget->recenterCamera(y, x, -z);

        mFollowCameraId = systemId;
529 530 531
    }
}

532 533 534 535 536 537 538 539 540 541
void
Pixhawk3DWidget::imageryParamsChanged(void)
{
    mImageryNode->setImageryType(mGlobalViewParams->imageryType());
    mImageryNode->setPath(mGlobalViewParams->imageryPath());

    const QVector3D& offset = mGlobalViewParams->imageryOffset();
    mImageryNode->setOffset(offset.x(), offset.y(), offset.z());
}

542
void
543
Pixhawk3DWidget::recenterActiveCamera(void)
544
{
545
    if (mFollowCameraId != -1)
546
    {
547 548
        UASInterface* uas = UASManager::instance()->getUASForId(mFollowCameraId);
        if (!uas)
549
        {
550
            return;
551 552
        }

553 554
        double x = 0.0, y = 0.0, z = 0.0;
        getPosition(uas, mGlobalViewParams->frame(), x, y, z);
555

556 557 558
        mCameraPos = QVector3D(x, y, z);

        m3DWidget->recenterCamera(y, x, -z);
559 560 561
    }
}

562
void
563
Pixhawk3DWidget::modelChanged(int systemId, int index)
564
{
565
    if (!mSystemContainerMap.contains(systemId))
566
    {
567
        return;
568
    }
569

570 571 572 573 574 575
    SystemContainer& systemData = mSystemContainerMap[systemId];
    osg::ref_ptr<SystemGroupNode>& systemGroupNode = m3DWidget->systemGroup(systemId);

    systemGroupNode->egocentricMap()->removeChild(systemData.modelNode());
    systemData.modelNode() = systemData.models().at(index);
    systemGroupNode->egocentricMap()->addChild(systemData.modelNode());
576 577
}

578
void
579
Pixhawk3DWidget::setBirdEyeView(void)
580
{
581
    mViewParamWidget->setFollowCameraId(-1);
582

583
    m3DWidget->rotateCamera(0.0, 0.0, 0.0);
584
    m3DWidget->setCameraDistance(100.0);
585
}
586

587 588 589
void
Pixhawk3DWidget::loadTerrainModel(void)
{
Don Gagne's avatar
Don Gagne committed
590
    QString filename = QGCFileDialog::getOpenFileName(this, "Load Terrain Model",
591
                                                    QStandardPaths::writableLocation(QStandardPaths::DesktopLocation),
592 593 594 595 596 597 598 599 600 601 602 603 604 605
                                                    tr("Collada (*.dae)"));

    if (filename.isNull())
    {
        return;
    }

    osg::ref_ptr<osg::Node> node =
        osgDB::readNodeFile(filename.toStdString().c_str());

    if (node)
    {
        if (mTerrainNode.get())
        {
606
            mTerrainPAT->removeChild(mTerrainNode);
607 608
        }
        mTerrainNode = node;
609 610 611
        mTerrainNode->setName("terrain");
        mTerrainPAT->addChild(mTerrainNode);

612 613
        mGlobalViewParams->terrainPositionOffset() = QVector3D();
        mGlobalViewParams->terrainAttitudeOffset() = QVector3D();
614 615

        mTerrainPAT->setPosition(osg::Vec3d(0.0, 0.0, 0.0));
616
        mTerrainPAT->setAttitude(osg::Quat(0.0, osg::Vec3d(0.0f, 0.0f, 1.0f),
617 618
                                           0.0, osg::Vec3d(1.0f, 0.0f, 0.0f),
                                           0.0, osg::Vec3d(0.0f, 1.0f, 0.0f)));
619 620 621
    }
    else
    {
Don Gagne's avatar
Don Gagne committed
622 623
        QGCMessageBox::warning(tr("Error loading model"),
                               tr("Error: Unable to load terrain model (%1).").arg(filename));
624 625 626
    }
}

627
void
628
Pixhawk3DWidget::selectTargetHeading(void)
629
{
630
    if (!mActiveUAS)
631 632 633
    {
        return;
    }
634

635 636
    osg::Vec2d p;

637
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
638
    {
639
        double altitude = mActiveUAS->getAltitudeAMSL();
640

641 642
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), altitude);
643

644
        p.set(cursorWorldCoords.x(), cursorWorldCoords.y());
645
    }
646
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
647
    {
648
        double z = mActiveUAS->getLocalZ();
649

650 651
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);
652

653
        p.set(cursorWorldCoords.x(), cursorWorldCoords.y());
654
    }
655

656 657 658
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

659
    target.setW(atan2(p.y() - target.y(), p.x() - target.x()));
660 661 662 663 664
}

void
Pixhawk3DWidget::selectTarget(void)
{
665
    if (!mActiveUAS)
666 667 668
    {
        return;
    }
669
    if (!mActiveUAS->getParamManager())
670 671 672
    {
        return;
    }
673

674 675 676 677
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
678
    {
679
        double altitude = mActiveUAS->getAltitudeAMSL();
680

681 682
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, altitude);
683

684
        QVariant zTarget;
685
        if (!mActiveUAS->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
686 687 688 689
        {
            zTarget = -altitude;
        }

690
        target = QVector4D(cursorWorldCoords.x(), cursorWorldCoords.y(),
691
                           zTarget.toReal(), 0.0);
692
    }
693
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
694
    {
695
        double z = mActiveUAS->getLocalZ();
696

697 698
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, -z);
699

700
        QVariant zTarget;
701
        if (!mActiveUAS->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
702 703 704 705
        {
            zTarget = z;
        }

706
        target = QVector4D(cursorWorldCoords.x(), cursorWorldCoords.y(),
707
                           zTarget.toReal(), 0.0);
708
    }
709

710
    int systemId = mActiveUAS->getUASID();
711

712 713 714 715 716 717 718
    QMap<int, SystemViewParamsPtr>::iterator it = mSystemViewParamMap.find(systemId);
    if (it != mSystemViewParamMap.end())
    {
        it.value()->displayTarget() = true;
    }

    mMode = SELECT_TARGET_HEADING_MODE;
719 720 721 722 723 724 725
}

void
Pixhawk3DWidget::setTarget(void)
{
    selectTargetHeading();

726 727 728 729 730
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

    mActiveUAS->setTargetPosition(target.x(), target.y(), target.z(),
                                  osg::RadiansToDegrees(target.w()));
731 732
}

733 734 735
void
Pixhawk3DWidget::insertWaypoint(void)
{
736
    if (!mActiveUAS)
737 738 739
    {
        return;
    }
740

741
    Waypoint* wp = NULL;
742
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
743
    {
744 745
        double latitude = mActiveUAS->getLatitude();
        double longitude = mActiveUAS->getLongitude();
746
        double altitude = mActiveUAS->getAltitudeAMSL();
747 748 749 750
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

751 752
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, altitude);
753

754
        Imagery::UTMtoLL(cursorWorldCoords.x(), cursorWorldCoords.y(), utmZone,
755 756
                         latitude, longitude);

757
        wp = new Waypoint(0, longitude, latitude, altitude, 0.0, 0.25);
758
    }
759
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
760
    {
761
        double z = mActiveUAS->getLocalZ();
762

763 764
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, -z);
765

766 767
        wp = new Waypoint(0, cursorWorldCoords.x(),
                          cursorWorldCoords.y(), z, 0.0, 0.25);
768 769 770 771
    }

    if (wp)
    {
772 773
        wp->setFrame(mGlobalViewParams->frame());
        mActiveUAS->getWaypointManager()->addWaypointEditable(wp);
774 775
    }

776 777
    mSelectedWpIndex = wp->getId();
    mMode = MOVE_WAYPOINT_HEADING_MODE;
778 779 780
}

void
781
Pixhawk3DWidget::moveWaypointPosition(void)
782
{
783
    if (mMode != MOVE_WAYPOINT_POSITION_MODE)
784
    {
785
        mMode = MOVE_WAYPOINT_POSITION_MODE;
786 787 788
        return;
    }

789
    if (!mActiveUAS)
790 791 792 793
    {
        return;
    }

794
    const QList<Waypoint *> waypoints =
795 796
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
797

798
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
799
    {
800 801
        double latitude = mActiveUAS->getLatitude();
        double longitude = mActiveUAS->getLongitude();
802
        double altitude = mActiveUAS->getAltitudeAMSL();
803 804 805 806
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

807 808
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), altitude);
809

810
        Imagery::UTMtoLL(cursorWorldCoords.x(), cursorWorldCoords.y(),
811
                         utmZone, latitude, longitude);
812 813 814 815

        waypoint->setX(longitude);
        waypoint->setY(latitude);
    }
816
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
817
    {
818
        double z = mActiveUAS->getLocalZ();
819

820 821
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);
822

823 824
        waypoint->setX(cursorWorldCoords.x());
        waypoint->setY(cursorWorldCoords.y());
825 826 827
    }
}

828 829 830
void
Pixhawk3DWidget::moveWaypointHeading(void)
{
831
    if (mMode != MOVE_WAYPOINT_HEADING_MODE)
832
    {
833
        mMode = MOVE_WAYPOINT_HEADING_MODE;
834 835 836
        return;
    }

837
    if (!mActiveUAS)
838 839 840 841
    {
        return;
    }

842
    const QList<Waypoint *> waypoints =
843 844
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
845 846 847

    double x = 0.0, y = 0.0, z = 0.0;

848
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
849 850 851 852 853 854 855
    {
        double latitude = waypoint->getY();
        double longitude = waypoint->getX();
        z = -waypoint->getZ();
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
    }
856
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
857
    {
858
        z = mActiveUAS->getLocalZ();
859 860
    }

861 862
    QPointF cursorWorldCoords =
        m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);
863

864 865
    double yaw = atan2(cursorWorldCoords.y() - waypoint->getY(),
                       cursorWorldCoords.x() - waypoint->getX());
866 867 868 869 870
    yaw = osg::RadiansToDegrees(yaw);

    waypoint->setYaw(yaw);
}

871 872 873
void
Pixhawk3DWidget::deleteWaypoint(void)
{
874
    if (mActiveUAS)
875
    {
876
        mActiveUAS->getWaypointManager()->removeWaypoint(mSelectedWpIndex);
877 878 879 880 881 882
    }
}

void
Pixhawk3DWidget::setWaypointAltitude(void)
{
883
    if (!mActiveUAS)
884 885 886
    {
        return;
    }
887

888
    bool ok;
889
    const QList<Waypoint *> waypoints =
890 891
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
892

893
    double altitude = waypoint->getZ();
894
    if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
895 896 897 898 899
    {
        altitude = -altitude;
    }

    double newAltitude =
900
        QInputDialog::getDouble(this, tr("Set altitude of waypoint %1").arg(mSelectedWpIndex),
901 902 903
                                tr("Altitude (m):"), waypoint->getZ(), -1000.0, 1000.0, 1, &ok);
    if (ok)
    {
904
        if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
905 906 907
        {
            waypoint->setZ(newAltitude);
        }
908
        else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
909 910
        {
            waypoint->setZ(-newAltitude);
911
        }
912 913 914 915 916 917
    }
}

void
Pixhawk3DWidget::clearAllWaypoints(void)
{
918
    if (mActiveUAS)
919
    {
920
        const QList<Waypoint *> waypoints =
921
            mActiveUAS->getWaypointManager()->getWaypointEditableList();
922 923
        for (int i = waypoints.size() - 1; i >= 0; --i)
        {
924
            mActiveUAS->getWaypointManager()->removeWaypoint(i);
925
        }
926 927 928
    }
}

929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027
void
Pixhawk3DWidget::moveImagery(void)
{
    if (mMode != MOVE_IMAGERY_MODE)
    {
        mMode = MOVE_IMAGERY_MODE;
        return;
    }

    if (!mActiveUAS)
    {
        return;
    }

    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
    {
        return;
    }

    double z = mActiveUAS->getLocalZ();

    QPointF cursorWorldCoords =
        m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);

    QVector3D& offset = mGlobalViewParams->imageryOffset();
    offset.setX(cursorWorldCoords.x());
    offset.setY(cursorWorldCoords.y());

    mImageryNode->setOffset(offset.x(), offset.y(), offset.z());
}

void
Pixhawk3DWidget::moveTerrain(void)
{
    if (mMode != MOVE_TERRAIN_MODE)
    {
        mMode = MOVE_TERRAIN_MODE;
        return;
    }

    if (!mActiveUAS)
    {
        return;
    }

    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
    {
        return;
    }

    double z = mActiveUAS->getLocalZ();

    QPointF cursorWorldCoords =
        m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);

    QVector3D& positionOffset = mGlobalViewParams->terrainPositionOffset();
    positionOffset.setX(cursorWorldCoords.x());
    positionOffset.setY(cursorWorldCoords.y());

    mTerrainPAT->setPosition(osg::Vec3d(positionOffset.y(), positionOffset.x(), -positionOffset.z()));
}

void
Pixhawk3DWidget::rotateTerrain(void)
{
    if (mMode != ROTATE_TERRAIN_MODE)
    {
        mMode = ROTATE_TERRAIN_MODE;
        return;
    }

    if (!mActiveUAS)
    {
        return;
    }

    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
    {
        return;
    }

    double z = mActiveUAS->getLocalZ();

    QPointF cursorWorldCoords =
        m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);

    const QVector3D& positionOffset = mGlobalViewParams->terrainPositionOffset();
    QVector3D& attitudeOffset = mGlobalViewParams->terrainAttitudeOffset();

    double yaw = atan2(cursorWorldCoords.y() - positionOffset.y(),
                       cursorWorldCoords.x() - positionOffset.x());

    attitudeOffset.setZ(yaw);

    mTerrainPAT->setAttitude(osg::Quat(- attitudeOffset.z(), osg::Vec3d(0.0f, 0.0f, 1.0f),
                                       attitudeOffset.y(), osg::Vec3d(1.0f, 0.0f, 0.0f),
                                       attitudeOffset.x(), osg::Vec3d(0.0f, 1.0f, 0.0f)));
}

1028 1029 1030 1031 1032 1033 1034
void
Pixhawk3DWidget::sizeChanged(int width, int height)
{
    resizeHUD(width, height);
}

void
1035
Pixhawk3DWidget::updateWidget(void)
1036 1037 1038 1039
{
    MAV_FRAME frame = mGlobalViewParams->frame();

    // set node visibility
1040
    m3DWidget->worldMap()->setChildValue(mTerrainPAT,
1041
                                         mGlobalViewParams->displayTerrain());
1042
    m3DWidget->worldMap()->setChildValue(mWorldGridNode,
1043
                                         mGlobalViewParams->displayWorldGrid());
1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062
    if (mGlobalViewParams->imageryType() == Imagery::BLANK_MAP)
    {
        m3DWidget->worldMap()->setChildValue(mImageryNode, false);
    }
    else
    {
        m3DWidget->worldMap()->setChildValue(mImageryNode, true);
    }

    // set system-specific node visibility
    QMutableMapIterator<int, SystemViewParamsPtr> it(mSystemViewParamMap);
    while (it.hasNext())
    {
        it.next();

        osg::ref_ptr<SystemGroupNode>& systemNode = m3DWidget->systemGroup(it.key());
        SystemContainer& systemData = mSystemContainerMap[it.key()];
        const SystemViewParamsPtr& systemViewParams = it.value();

1063 1064 1065 1066
        osg::ref_ptr<osg::Switch>& allocentricMap = systemNode->allocentricMap();
        allocentricMap->setChildValue(systemData.setpointGroupNode(),
                                      systemViewParams->displaySetpoints());

1067 1068 1069
        osg::ref_ptr<osg::Switch>& rollingMap = systemNode->rollingMap();
        rollingMap->setChildValue(systemData.localGridNode(),
                                  systemViewParams->displayLocalGrid());
1070 1071
        rollingMap->setChildValue(systemData.orientationNode(),
                                  systemViewParams->displayTrails());
1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108
        rollingMap->setChildValue(systemData.pointCloudNode(),
                                  systemViewParams->displayPointCloud());
        rollingMap->setChildValue(systemData.targetNode(),
                                  systemViewParams->displayTarget());
        rollingMap->setChildValue(systemData.trailNode(),
                                  systemViewParams->displayTrails());
        rollingMap->setChildValue(systemData.waypointGroupNode(),
                                  systemViewParams->displayWaypoints());
    }

    if (mFollowCameraId != -1)
    {
        UASInterface* uas = UASManager::instance()->getUASForId(mFollowCameraId);
        if (uas)
        {
            double x = 0.0, y = 0.0, z = 0.0;
            getPosition(uas, mGlobalViewParams->frame(), x, y, z);

            double dx = y - mCameraPos.y();
            double dy = x - mCameraPos.x();
            double dz = mCameraPos.z() - z;

            m3DWidget->moveCamera(dx, dy, dz);

            mCameraPos = QVector3D(x, y, z);
        }
    }
    else
    {
        if (!mInitCameraPos && mActiveUAS)
        {
            double x = 0.0, y = 0.0, z = 0.0;
            getPosition(mActiveUAS, frame, x, y, z);
            m3DWidget->recenterCamera(y, x, -z);

            mCameraPos = QVector3D(x, y, z);

1109
            setBirdEyeView();
1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135
            mInitCameraPos = true;
        }
    }

    // update system-specific data
    it.toFront();
    while (it.hasNext())
    {
        it.next();

        int systemId = it.key();

        UASInterface* uas = UASManager::instance()->getUASForId(systemId);

        SystemContainer& systemData = mSystemContainerMap[systemId];
        SystemViewParamsPtr& systemViewParams = it.value();

        double x = 0.0;
        double y = 0.0;
        double z = 0.0;
        double roll = 0.0;
        double pitch = 0.0;
        double yaw = 0.0;

        getPose(uas, frame, x, y, z, roll, pitch, yaw);

1136 1137 1138 1139 1140 1141 1142 1143
        if (systemViewParams->displaySetpoints())
        {

        }
        else
        {
            systemData.setpointGroupNode()->removeChildren(0, systemData.setpointGroupNode()->getNumChildren());
        }
1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157
        if (systemViewParams->displayTarget())
        {
            if (systemData.target().isNull())
            {
                systemViewParams->displayTarget() = false;
            }
            else
            {
                updateTarget(uas, frame, x, y, z, systemData.target(),
                             systemData.targetNode());
            }
        }
        if (systemViewParams->displayTrails())
        {
1158
            updateTrails(x, y, z, systemData.trailNode(), systemData.orientationNode(),
1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173
                         systemData.trailMap(), systemData.trailIndexMap());
        }
        else
        {
            systemData.trailMap().clear();
        }
        if (systemViewParams->displayWaypoints())
        {
            updateWaypoints(uas, frame, systemData.waypointGroupNode());
        }
    }

    if (frame == MAV_FRAME_GLOBAL &&
        mGlobalViewParams->imageryType() != Imagery::BLANK_MAP)
    {
1174
//        updateImagery(x, y, z, utmZone);
1175 1176
    }

1177 1178 1179 1180
    if (mActiveUAS)
    {
      updateHUD(mActiveUAS, frame);
    }
1181 1182 1183 1184 1185 1186 1187

    layout()->update();
}

void
Pixhawk3DWidget::addModels(QVector< osg::ref_ptr<osg::Node> >& models,
                           const QColor& systemColor)
1188 1189
{
    QDir directory("models");
lm's avatar
lm committed
1190
    QStringList files = directory.entryList(QStringList("*.osg"), QDir::Files);
1191 1192

    // add Pixhawk Bravo model
1193
    models.push_back(PixhawkCheetahNode::create(systemColor));
1194

hengli's avatar
hengli committed
1195 1196 1197
    // add sphere of 0.05m radius
    osg::ref_ptr<osg::Sphere> sphere = new osg::Sphere(osg::Vec3f(0.0f, 0.0f, 0.0f), 0.05f);
    osg::ref_ptr<osg::ShapeDrawable> sphereDrawable = new osg::ShapeDrawable(sphere);
1198
    sphereDrawable->setColor(osg::Vec4f(systemColor.redF(), systemColor.greenF(), systemColor.blueF(), 1.0f));
hengli's avatar
hengli committed
1199 1200 1201
    osg::ref_ptr<osg::Geode> sphereGeode = new osg::Geode;
    sphereGeode->addDrawable(sphereDrawable);
    sphereGeode->setName("Sphere (0.1m)");
1202
    models.push_back(sphereGeode);
hengli's avatar
hengli committed
1203

1204
    // add all other models in folder
1205 1206
    for (int i = 0; i < files.size(); ++i)
    {
1207
        osg::ref_ptr<osg::Node> node =
1208
            osgDB::readNodeFile(directory.absoluteFilePath(files[i]).toStdString().c_str());
1209

1210 1211
        if (node)
        {
1212
            models.push_back(node);
1213 1214 1215
        }
        else
        {
1216
            printf("%s\n", QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
lm's avatar
lm committed
1217
        }
1218 1219 1220 1221 1222 1223
    }
}

void
Pixhawk3DWidget::buildLayout(void)
{
1224 1225 1226
    QPushButton* clearDataButton = new QPushButton(this);
    clearDataButton->setText("Clear Data");

1227
    QPushButton* viewParamWindowButton = new QPushButton(this);
1228
    viewParamWindowButton->setCheckable(true);
1229
    viewParamWindowButton->setText("View Parameters");
1230

1231 1232
    QHBoxLayout* layoutTop = new QHBoxLayout;
    layoutTop->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding));
1233
    layoutTop->addWidget(clearDataButton);
1234
    layoutTop->addWidget(viewParamWindowButton);
1235 1236 1237 1238

    QPushButton* recenterButton = new QPushButton(this);
    recenterButton->setText("Recenter Camera");

1239 1240
    QPushButton* birdEyeViewButton = new QPushButton(this);
    birdEyeViewButton->setText("Bird's Eye View");
1241

1242 1243 1244
    QPushButton* loadTerrainModelButton = new QPushButton(this);
    loadTerrainModelButton->setText("Load Terrain Model");

1245 1246
    QHBoxLayout* layoutBottom = new QHBoxLayout;
    layoutBottom->addWidget(recenterButton);
1247
    layoutBottom->addWidget(birdEyeViewButton);
1248
    layoutBottom->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding));
1249
    layoutBottom->addWidget(loadTerrainModelButton);
1250 1251 1252 1253

    QGridLayout* layout = new QGridLayout(this);
    layout->setMargin(0);
    layout->setSpacing(2);
1254 1255 1256
    layout->addLayout(layoutTop, 0, 0);
    layout->addWidget(m3DWidget, 1, 0);
    layout->addLayout(layoutBottom, 2, 0);
1257 1258 1259
    layout->setRowStretch(0, 1);
    layout->setRowStretch(1, 100);
    layout->setRowStretch(2, 1);
1260

1261 1262
    connect(clearDataButton, SIGNAL(clicked()),
            this, SLOT(clearData()));
1263 1264 1265 1266
    connect(viewParamWindowButton, SIGNAL(clicked()),
            this, SLOT(showViewParamWindow()));
    connect(recenterButton, SIGNAL(clicked()),
            this, SLOT(recenterActiveCamera()));
1267 1268
    connect(birdEyeViewButton, SIGNAL(clicked()),
            this, SLOT(setBirdEyeView()));
1269 1270
    connect(loadTerrainModelButton, SIGNAL(clicked()),
            this, SLOT(loadTerrainModel()));
1271 1272
}

1273
void
1274
Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
1275
{
1276 1277
    QWidget::keyPressEvent(event);
    if (event->isAccepted())
1278
    {
1279 1280 1281
        return;
    }

1282
    m3DWidget->handleKeyPressEvent(event);
1283 1284
}

1285
void
1286
Pixhawk3DWidget::keyReleaseEvent(QKeyEvent* event)
1287
{
1288 1289
    QWidget::keyReleaseEvent(event);
    if (event->isAccepted())
1290
    {
1291
        return;
1292 1293
    }

1294
    m3DWidget->handleKeyReleaseEvent(event);
1295 1296
}

1297 1298 1299
void
Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
{
1300 1301 1302 1303 1304 1305
    QWidget::mousePressEvent(event);
    if (event->isAccepted())
    {
        return;
    }

1306 1307
    if (event->button() == Qt::LeftButton)
    {
1308
        if (mMode == SELECT_TARGET_HEADING_MODE)
1309
        {
1310
            setTarget();
1311
            event->accept();
1312 1313
        }

1314
        if (mMode != DEFAULT_MODE)
1315
        {
1316 1317
            mMode = DEFAULT_MODE;
            event->accept();
1318
        }
1319 1320 1321 1322
    }
    else if (event->button() == Qt::RightButton)
    {
        if (m3DWidget->getSceneData() && mActiveUAS)
1323
        {
1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366
            mSelectedWpIndex = -1;
            bool mouseOverImagery = false;
            bool mouseOverTerrain = false;

            SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
            osg::ref_ptr<WaypointGroupNode>& waypointGroupNode = systemData.waypointGroupNode();

            osgUtil::LineSegmentIntersector::Intersections intersections;

            QPoint widgetMousePos = m3DWidget->mapFromParent(event->pos());

            if (m3DWidget->computeIntersections(widgetMousePos.x(),
                                                m3DWidget->height() - widgetMousePos.y(),
                                                intersections))
            {
                for (osgUtil::LineSegmentIntersector::Intersections::iterator
                     it = intersections.begin(); it != intersections.end(); it++)
                {
                    for (uint i = 0 ; i < it->nodePath.size(); ++i)
                    {
                        osg::Node* node = it->nodePath[i];
                        std::string nodeName = node->getName();

                        if (nodeName.substr(0, 2).compare("wp") == 0)
                        {
                            if (node->getParent(0)->getParent(0) == waypointGroupNode.get())
                            {
                                mSelectedWpIndex = atoi(nodeName.substr(2).c_str());
                            }
                        }
                        else if (nodeName.compare("imagery") == 0)
                        {
                            mouseOverImagery = true;
                        }
                        else if (nodeName.compare("terrain") == 0)
                        {
                            mouseOverTerrain = true;
                        }
                    }
                }
            }

            QMenu menu;
1367
            if (mSelectedWpIndex == -1)
1368
            {
1369
                mCachedMousePos = event->pos();
1370

1371
                menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
1372 1373 1374
            }
            else
            {
1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386
                QString text;
                text = QString("Move waypoint %1").arg(QString::number(mSelectedWpIndex));
                menu.addAction(text, this, SLOT(moveWaypointPosition()));

                text = QString("Change heading of waypoint %1").arg(QString::number(mSelectedWpIndex));
                menu.addAction(text, this, SLOT(moveWaypointHeading()));

                text = QString("Change altitude of waypoint %1").arg(QString::number(mSelectedWpIndex));
                menu.addAction(text, this, SLOT(setWaypointAltitude()));

                text = QString("Delete waypoint %1").arg(QString::number(mSelectedWpIndex));
                menu.addAction(text, this, SLOT(deleteWaypoint()));
1387 1388
            }

1389
            menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
1390
            menu.addSeparator();
1391 1392 1393 1394
            menu.addAction("Select target", this, SLOT(selectTarget()));

            if (mouseOverImagery)
            {
1395
                menu.addSeparator();
1396 1397 1398 1399
                menu.addAction("Move imagery", this, SLOT(moveImagery()));
            }
            if (mouseOverTerrain)
            {
1400
                menu.addSeparator();
1401 1402 1403 1404 1405 1406
                menu.addAction("Move terrain", this, SLOT(moveTerrain()));
                menu.addAction("Rotate terrain", this, SLOT(rotateTerrain()));
                menu.addAction("Edit terrain parameters", this, SLOT(showTerrainParamWindow()));
            }

            menu.exec(event->globalPos());
1407 1408 1409 1410 1411

            event->accept();
        }
    }

1412

1413
    m3DWidget->handleMousePressEvent(event);
1414 1415
}

1416
void
1417
Pixhawk3DWidget::mouseReleaseEvent(QMouseEvent* event)
1418
{
1419 1420 1421 1422 1423
    QWidget::mouseReleaseEvent(event);
    if (event->isAccepted())
    {
        return;
    }
1424

1425
    m3DWidget->handleMouseReleaseEvent(event);
1426 1427
}

1428 1429 1430
void
Pixhawk3DWidget::mouseMoveEvent(QMouseEvent* event)
{
1431 1432 1433 1434 1435 1436
    QWidget::mouseMoveEvent(event);
    if (event->isAccepted())
    {
        return;
    }

1437
    switch (mMode)
1438
    {
1439
    case SELECT_TARGET_HEADING_MODE:
1440
        selectTargetHeading();
1441
        event->accept();
1442 1443
        break;
    case MOVE_WAYPOINT_POSITION_MODE:
1444
        moveWaypointPosition();
1445
        event->accept();
1446 1447
        break;
    case MOVE_WAYPOINT_HEADING_MODE:
1448
        moveWaypointHeading();
1449
        event->accept();
1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464
        break;
    case MOVE_IMAGERY_MODE:
        moveImagery();
        event->accept();
        break;
    case MOVE_TERRAIN_MODE:
        moveTerrain();
        event->accept();
        break;
    case ROTATE_TERRAIN_MODE:
        rotateTerrain();
        event->accept();
        break;
    default:
        {}
1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484
    }

    m3DWidget->handleMouseMoveEvent(event);
}

void
Pixhawk3DWidget::wheelEvent(QWheelEvent* event)
{
    QWidget::wheelEvent(event);
    if (event->isAccepted())
    {
        return;
    }

    m3DWidget->handleWheelEvent(event);
}

void
Pixhawk3DWidget::showEvent(QShowEvent* event)
{
1485 1486
    Q_UNUSED(event);

1487 1488 1489 1490 1491 1492
    emit visibilityChanged(true);
}

void
Pixhawk3DWidget::hideEvent(QHideEvent* event)
{
1493 1494
    Q_UNUSED(event);

1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508
    emit visibilityChanged(false);
}

void
Pixhawk3DWidget::initializeSystem(int systemId, const QColor& systemColor)
{
    SystemViewParamsPtr& systemViewParams = mSystemViewParamMap[systemId];
    SystemContainer& systemData = mSystemContainerMap[systemId];
    osg::ref_ptr<SystemGroupNode>& systemNode = m3DWidget->systemGroup(systemId);

    // generate grid model
    systemData.localGridNode() = createLocalGrid();
    systemNode->rollingMap()->addChild(systemData.localGridNode(), false);

1509 1510 1511 1512
    // generate orientation model
    systemData.orientationNode() = new osg::Group;
    systemNode->rollingMap()->addChild(systemData.orientationNode(), false);

1513 1514 1515 1516
    // generate point cloud model
    systemData.pointCloudNode() = createPointCloud();
    systemNode->rollingMap()->addChild(systemData.pointCloudNode(), false);

1517 1518 1519 1520
    // generate setpoint model
    systemData.setpointGroupNode() = new osg::Group;
    systemNode->allocentricMap()->addChild(systemData.setpointGroupNode(), false);

1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549
    // generate target model
    systemData.targetNode() = createTarget(systemColor);
    systemNode->rollingMap()->addChild(systemData.targetNode(), false);

    // generate empty trail model
    systemData.trailNode() = new osg::Geode;
    systemNode->rollingMap()->addChild(systemData.trailNode(), false);

    // generate waypoint model
    systemData.waypointGroupNode() = new WaypointGroupNode(systemColor);
    systemData.waypointGroupNode()->init();
    systemNode->rollingMap()->addChild(systemData.waypointGroupNode(), false);

    systemData.rgbImageNode() = new ImageWindowGeode;
    systemData.rgbImageNode()->init("RGB Image", osg::Vec4(0.0f, 0.0f, 0.1f, 1.0f),
                                    m3DWidget->font());
    m3DWidget->hudGroup()->addChild(systemData.rgbImageNode(), false);

    systemData.depthImageNode() = new ImageWindowGeode;
    systemData.depthImageNode()->init("Depth Image", osg::Vec4(0.0f, 0.0f, 0.1f, 1.0f),
                                      m3DWidget->font());
    m3DWidget->hudGroup()->addChild(systemData.depthImageNode(), false);

    // find available models
    addModels(systemData.models(), systemColor);
    systemViewParams->modelNames();
    for (int i = 0; i < systemData.models().size(); ++i)
    {
        systemViewParams->modelNames().push_back(systemData.models()[i]->getName().c_str());
1550
    }
1551

1552 1553 1554 1555 1556
    systemData.modelNode() = systemData.models().front();
    systemNode->egocentricMap()->addChild(systemData.modelNode());

    connect(systemViewParams.data(), SIGNAL(modelChangedSignal(int,int)),
            this, SLOT(modelChanged(int,int)));
1557 1558
}

1559
void
1560 1561 1562
Pixhawk3DWidget::getPose(UASInterface* uas,
                         MAV_FRAME frame,
                         double& x, double& y, double& z,
1563
                         double& roll, double& pitch, double& yaw,
1564
                         QString& utmZone) const
1565
{
1566 1567 1568 1569
    if (!uas)
    {
        return;
    }
1570

1571 1572 1573 1574
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
1575
        double altitude = uas->getAltitudeAMSL();
1576 1577 1578

        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
        z = -altitude;
1579
    }
1580 1581 1582 1583 1584
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
        x = uas->getLocalX();
        y = uas->getLocalY();
        z = uas->getLocalZ();
1585
    }
1586 1587 1588 1589

    roll = uas->getRoll();
    pitch = uas->getPitch();
    yaw = uas->getYaw();
1590 1591 1592
}

void
1593 1594 1595 1596
Pixhawk3DWidget::getPose(UASInterface* uas,
                         MAV_FRAME frame,
                         double& x, double& y, double& z,
                         double& roll, double& pitch, double& yaw) const
1597 1598
{
    QString utmZone;
1599
    getPose(uas, frame, x, y, z, roll, pitch, yaw, utmZone);
1600 1601 1602
}

void
1603 1604 1605 1606
Pixhawk3DWidget::getPosition(UASInterface* uas,
                             MAV_FRAME frame,
                             double& x, double& y, double& z,
                             QString& utmZone) const
1607
{
1608
    if (!uas)
Lorenz Meier's avatar
Lorenz Meier committed
1609
    {
1610 1611
        return;
    }
1612

1613 1614 1615 1616
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
1617
        double altitude = uas->getAltitudeAMSL();
1618 1619 1620 1621 1622 1623 1624 1625 1626

        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
        z = -altitude;
    }
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
        x = uas->getLocalX();
        y = uas->getLocalY();
        z = uas->getLocalZ();
1627 1628 1629 1630
    }
}

void
1631 1632 1633
Pixhawk3DWidget::getPosition(UASInterface* uas,
                             MAV_FRAME frame,
                             double& x, double& y, double& z) const
1634 1635
{
    QString utmZone;
1636
    getPosition(uas, frame, x, y, z, utmZone);
1637 1638
}

1639
osg::ref_ptr<osg::Geode>
1640
Pixhawk3DWidget::createLocalGrid(void)
1641 1642
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
1643 1644 1645 1646
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
1647

1648
    float radius = 5.0f;
1649 1650
    float resolution = 0.25f;

1651 1652
    osg::ref_ptr<osg::Vec3Array> fineCoords(new osg::Vec3Array);
    osg::ref_ptr<osg::Vec3Array> coarseCoords(new osg::Vec3Array);
1653

1654
    // draw a 10m x 10m grid with 0.25m resolution
1655 1656
    for (float i = -radius; i <= radius; i += resolution)
    {
1657
        if (fabs(i / 1.0f - floor(i / 1.0f)) < 0.01f)
1658
        {
1659 1660 1661 1662
            coarseCoords->push_back(osg::Vec3(i, -radius, 0.0f));
            coarseCoords->push_back(osg::Vec3(i, radius, 0.0f));
            coarseCoords->push_back(osg::Vec3(-radius, i, 0.0f));
            coarseCoords->push_back(osg::Vec3(radius, i, 0.0f));
1663 1664 1665
        }
        else
        {
1666 1667 1668 1669 1670
            fineCoords->push_back(osg::Vec3(i, -radius, 0.0f));
            fineCoords->push_back(osg::Vec3(i, radius, 0.0f));
            fineCoords->push_back(osg::Vec3(-radius, i, 0.0f));
            fineCoords->push_back(osg::Vec3(radius, i, 0.0f));
        }
1671 1672
    }

1673 1674
    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);
1675 1676 1677

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
1678 1679 1680 1681 1682 1683
    fineGeometry->setColorArray(color);
    coarseGeometry->setColorArray(color);
    fineGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);
    coarseGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);

    fineGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES,
1684
                                  0, fineCoords->size()));
1685
    coarseGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0,
1686
                                    coarseCoords->size()));
1687 1688 1689 1690 1691 1692

    osg::ref_ptr<osg::StateSet> fineStateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> fineLinewidth(new osg::LineWidth());
    fineLinewidth->setWidth(0.25f);
    fineStateset->setAttributeAndModes(fineLinewidth, osg::StateAttribute::ON);
    fineStateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766
    fineStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    fineStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
    fineGeometry->setStateSet(fineStateset);

    osg::ref_ptr<osg::StateSet> coarseStateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> coarseLinewidth(new osg::LineWidth());
    coarseLinewidth->setWidth(1.0f);
    coarseStateset->setAttributeAndModes(coarseLinewidth, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
    coarseStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
    coarseGeometry->setStateSet(coarseStateset);

    return geode;
}

osg::ref_ptr<osg::Geode>
Pixhawk3DWidget::createWorldGrid(void)
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> axisGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
    geode->addDrawable(axisGeometry.get());

    float radius = 20.0f;
    float resolution = 1.0f;

    osg::ref_ptr<osg::Vec3Array> fineCoords(new osg::Vec3Array);
    osg::ref_ptr<osg::Vec3Array> coarseCoords(new osg::Vec3Array);

    // draw a 40m x 40m grid with 1.0m resolution
    for (float i = -radius; i <= radius; i += resolution)
    {
        if (fabs(i / 5.0f - floor(i / 5.0f)) < 0.01f)
        {
            coarseCoords->push_back(osg::Vec3(i, -radius, 0.0f));
            coarseCoords->push_back(osg::Vec3(i, radius, 0.0f));
            coarseCoords->push_back(osg::Vec3(-radius, i, 0.0f));
            coarseCoords->push_back(osg::Vec3(radius, i, 0.0f));
        }
        else
        {
            fineCoords->push_back(osg::Vec3(i, -radius, 0.0f));
            fineCoords->push_back(osg::Vec3(i, radius, 0.0f));
            fineCoords->push_back(osg::Vec3(-radius, i, 0.0f));
            fineCoords->push_back(osg::Vec3(radius, i, 0.0f));
        }
    }

    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
    fineGeometry->setColorArray(color);
    coarseGeometry->setColorArray(color);
    fineGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);
    coarseGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);

    fineGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES,
                                  0, fineCoords->size()));
    coarseGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0,
                                    coarseCoords->size()));

    osg::ref_ptr<osg::StateSet> fineStateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> fineLinewidth(new osg::LineWidth());
    fineLinewidth->setWidth(0.1f);
    fineStateset->setAttributeAndModes(fineLinewidth, osg::StateAttribute::ON);
    fineStateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
    fineStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    fineStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
1767 1768 1769 1770 1771 1772 1773
    fineGeometry->setStateSet(fineStateset);

    osg::ref_ptr<osg::StateSet> coarseStateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> coarseLinewidth(new osg::LineWidth());
    coarseLinewidth->setWidth(2.0f);
    coarseStateset->setAttributeAndModes(coarseLinewidth, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
1774 1775
    coarseStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
1776
    coarseGeometry->setStateSet(coarseStateset);
1777

1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811
    // add axes
    osg::ref_ptr<osg::Vec3Array> coords(new osg::Vec3Array(6));
    (*coords)[0] = (*coords)[2] = (*coords)[4] =
                                      osg::Vec3(0.0f, 0.0f, 0.0f);
    (*coords)[1] = osg::Vec3(0.0f, 1.0f, 0.0f);
    (*coords)[3] = osg::Vec3(1.0f, 0.0f, 0.0f);
    (*coords)[5] = osg::Vec3(0.0f, 0.0f, -1.0f);

    axisGeometry->setVertexArray(coords);

    osg::Vec4 redColor(1.0f, 0.0f, 0.0f, 0.0f);
    osg::Vec4 greenColor(0.0f, 1.0f, 0.0f, 0.0f);
    osg::Vec4 blueColor(0.0f, 0.0f, 1.0f, 0.0f);

    osg::ref_ptr<osg::Vec4Array> axisColors(new osg::Vec4Array(6));
    (*axisColors)[0] = redColor;
    (*axisColors)[1] = redColor;
    (*axisColors)[2] = greenColor;
    (*axisColors)[3] = greenColor;
    (*axisColors)[4] = blueColor;
    (*axisColors)[5] = blueColor;

    axisGeometry->setColorArray(axisColors);
    axisGeometry->setColorBinding(osg::Geometry::BIND_PER_VERTEX);

    axisGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0, 6));

    osg::ref_ptr<osg::StateSet> axisStateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> axisLinewidth(new osg::LineWidth());
    axisLinewidth->setWidth(4.0f);
    axisStateset->setAttributeAndModes(axisLinewidth, osg::StateAttribute::ON);
    axisStateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
    axisGeometry->setStateSet(axisStateset);

1812 1813 1814
    return geode;
}

1815
osg::ref_ptr<osg::Geometry>
1816
Pixhawk3DWidget::createTrail(const osg::Vec4& color)
1817
{
1818 1819
    osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry());
    geometry->setUseDisplayList(false);
1820

1821 1822
    osg::ref_ptr<osg::Vec3dArray> vertices(new osg::Vec3dArray());
    geometry->setVertexArray(vertices);
1823

1824 1825
    osg::ref_ptr<osg::DrawArrays> drawArrays(new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP));
    geometry->addPrimitiveSet(drawArrays);
1826

1827 1828 1829 1830
    osg::ref_ptr<osg::Vec4Array> colorArray(new osg::Vec4Array);
    colorArray->push_back(color);
    geometry->setColorArray(colorArray);
    geometry->setColorBinding(osg::Geometry::BIND_OVERALL);
1831 1832 1833 1834 1835 1836

    osg::ref_ptr<osg::StateSet> stateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> linewidth(new osg::LineWidth());
    linewidth->setWidth(1.0f);
    stateset->setAttributeAndModes(linewidth, osg::StateAttribute::ON);
    stateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
1837
    geometry->setStateSet(stateset);
1838

1839
    return geometry;
1840 1841
}

1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870
osg::ref_ptr<osg::Geometry>
Pixhawk3DWidget::createLink(const QColor& color)
{
    osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry());
    geometry->setUseDisplayList(false);

    osg::ref_ptr<osg::Vec3dArray> vertices(new osg::Vec3dArray());
    geometry->setVertexArray(vertices);

    osg::ref_ptr<osg::DrawArrays> drawArrays(new osg::DrawArrays(osg::PrimitiveSet::LINES));
    geometry->addPrimitiveSet(drawArrays);

    osg::ref_ptr<osg::Vec4Array> colorArray(new osg::Vec4Array);
    colorArray->push_back(osg::Vec4(color.redF(), color.greenF(), color.blueF(), 1.0f));
    geometry->setColorArray(colorArray);
    geometry->setColorBinding(osg::Geometry::BIND_OVERALL);

    osg::ref_ptr<osg::StateSet> stateset(new osg::StateSet);
    osg::ref_ptr<osg::LineWidth> linewidth(new osg::LineWidth());
    linewidth->setWidth(3.0f);
    stateset->setAttributeAndModes(linewidth, osg::StateAttribute::ON);
    stateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
    stateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    stateset->setMode(GL_BLEND, osg::StateAttribute::ON);
    geometry->setStateSet(stateset);

    return geometry;
}

1871
osg::ref_ptr<Imagery>
1872
Pixhawk3DWidget::createImagery(void)
1873
{
1874
    return osg::ref_ptr<Imagery>(new Imagery());
1875 1876
}

1877
osg::ref_ptr<osg::Geode>
1878
Pixhawk3DWidget::createPointCloud(void)
1879
{
1880
    int frameSize = 752 * 480;
1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895

    osg::ref_ptr<osg::Geode> geode(new osg::Geode);
    osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry);

    osg::ref_ptr<osg::Vec3Array> vertices(new osg::Vec3Array(frameSize));
    geometry->setVertexArray(vertices);

    osg::ref_ptr<osg::Vec4Array> colors(new osg::Vec4Array(frameSize));
    geometry->setColorArray(colors);
    geometry->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
    geometry->setUseDisplayList(false);

    geode->addDrawable(geometry);

    return geode;
1896 1897
}

1898
osg::ref_ptr<osg::Node>
1899
Pixhawk3DWidget::createTarget(const QColor& color)
1900 1901
{
    osg::ref_ptr<osg::PositionAttitudeTransform> pat =
1902
        new osg::PositionAttitudeTransform;
1903 1904 1905

    pat->setPosition(osg::Vec3d(0.0, 0.0, 0.0));

1906
    osg::ref_ptr<osg::Cone> cone = new osg::Cone(osg::Vec3f(0.0f, 0.0f, 0.0f), 0.2f, 0.6f);
1907
    osg::ref_ptr<osg::ShapeDrawable> coneDrawable = new osg::ShapeDrawable(cone);
1908
    coneDrawable->setColor(osg::Vec4f(color.redF(), color.greenF(), color.blueF(), 1.0f));
1909 1910 1911 1912
    coneDrawable->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
    osg::ref_ptr<osg::Geode> coneGeode = new osg::Geode;
    coneGeode->addDrawable(coneDrawable);
    coneGeode->setName("Target");
1913

1914
    pat->addChild(coneGeode);
1915 1916 1917 1918

    return pat;
}

1919 1920 1921 1922
void
Pixhawk3DWidget::setupHUD(void)
{
    osg::ref_ptr<osg::Vec4Array> hudColors(new osg::Vec4Array);
1923 1924
    hudColors->push_back(osg::Vec4(0.0f, 0.0f, 0.0f, 0.5f));
    hudColors->push_back(osg::Vec4(0.0f, 0.0f, 0.0f, 1.0f));
1925

1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939
    mHudBackgroundGeometry = new osg::Geometry;
    mHudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                            0, 4));
    mHudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                            4, 4));
    mHudBackgroundGeometry->setColorArray(hudColors);
    mHudBackgroundGeometry->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
    mHudBackgroundGeometry->setUseDisplayList(false);

    mStatusText = new osgText::Text;
    mStatusText->setCharacterSize(11);
    mStatusText->setFont(m3DWidget->font());
    mStatusText->setAxisAlignment(osgText::Text::SCREEN);
    mStatusText->setColor(osg::Vec4(255, 255, 255, 1));
1940

1941
    osg::ref_ptr<osg::Geode> statusGeode = new osg::Geode;
1942 1943 1944 1945 1946 1947 1948
    statusGeode->addDrawable(mHudBackgroundGeometry);
    statusGeode->addDrawable(mStatusText);
    m3DWidget->hudGroup()->addChild(statusGeode);

    mScaleGeode = new HUDScaleGeode;
    mScaleGeode->init(m3DWidget->font());
    m3DWidget->hudGroup()->addChild(mScaleGeode);
1949 1950 1951
}

void
1952
Pixhawk3DWidget::resizeHUD(int width, int height)
1953
{
1954
    int topHUDHeight = 25;
1955 1956
    int bottomHUDHeight = 25;

1957
    osg::Vec3Array* vertices = static_cast<osg::Vec3Array*>(mHudBackgroundGeometry->getVertexArray());
Lorenz Meier's avatar
Lorenz Meier committed
1958 1959
    if (vertices == NULL || vertices->size() != 8)
    {
1960
        osg::ref_ptr<osg::Vec3Array> newVertices = new osg::Vec3Array(8);
1961
        mHudBackgroundGeometry->setVertexArray(newVertices);
1962

1963
        vertices = static_cast<osg::Vec3Array*>(mHudBackgroundGeometry->getVertexArray());
1964 1965
    }

1966 1967 1968 1969
    (*vertices)[0] = osg::Vec3(0, height, -1);
    (*vertices)[1] = osg::Vec3(width, height, -1);
    (*vertices)[2] = osg::Vec3(width, height - topHUDHeight, -1);
    (*vertices)[3] = osg::Vec3(0, height - topHUDHeight, -1);
1970
    (*vertices)[4] = osg::Vec3(0, 0, -1);
1971 1972
    (*vertices)[5] = osg::Vec3(width, 0, -1);
    (*vertices)[6] = osg::Vec3(width, bottomHUDHeight, -1);
1973
    (*vertices)[7] = osg::Vec3(0, bottomHUDHeight, -1);
1974

1975
    mStatusText->setPosition(osg::Vec3(10, height - 15, -1.5));
1976

1977 1978
    QMutableMapIterator<int, SystemContainer> it(mSystemContainerMap);
    while (it.hasNext())
Lorenz Meier's avatar
Lorenz Meier committed
1979
    {
1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997
        it.next();

        SystemContainer& systemData = it.value();

        if (systemData.rgbImageNode().valid() &&
            systemData.depthImageNode().valid())
        {
            int windowWidth = (width - 20) / 2;
            int windowHeight = 3 * windowWidth / 4;
            systemData.rgbImageNode()->setAttributes(10,
                                                     (height - windowHeight) / 2,
                                                     windowWidth,
                                                     windowHeight);
            systemData.depthImageNode()->setAttributes(width / 2,
                                                       (height - windowHeight) / 2,
                                                       windowWidth,
                                                       windowHeight);
        }
1998 1999 2000 2001
    }
}

void
2002
Pixhawk3DWidget::updateHUD(UASInterface* uas, MAV_FRAME frame)
2003
{
LM's avatar
LM committed
2004
    if (!uas) return;
2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017
    // display pose of current system
    double x = 0.0;
    double y = 0.0;
    double z = 0.0;
    double roll = 0.0;
    double pitch = 0.0;
    double yaw = 0.0;
    QString utmZone;

    getPose(uas, frame, x, y, z, roll, pitch, yaw, utmZone);

    QPointF cursorPosition =
        m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), -z);
2018 2019 2020 2021

    std::ostringstream oss;
    oss.setf(std::ios::fixed, std::ios::floatfield);
    oss.precision(2);
2022 2023
    oss << "MAV " << uas->getUASID() << ": ";

Lorenz Meier's avatar
Lorenz Meier committed
2024 2025
    if (frame == MAV_FRAME_GLOBAL)
    {
2026
        double latitude, longitude;
2027
        Imagery::UTMtoLL(x, y, utmZone, latitude, longitude);
2028 2029

        double cursorLatitude, cursorLongitude;
2030
        Imagery::UTMtoLL(cursorPosition.x(), cursorPosition.y(),
2031 2032 2033 2034
                         utmZone, cursorLatitude, cursorLongitude);

        oss.precision(6);
        oss << " Lat = " << latitude <<
2035
            " Lon = " << longitude;
2036 2037

        oss.precision(2);
2038 2039 2040 2041
        oss << " Altitude = " << -z <<
            " r = " << roll <<
            " p = " << pitch <<
            " y = " << yaw;
2042 2043 2044

        oss.precision(6);
        oss << " Cursor [" << cursorLatitude <<
2045
            " " << cursorLongitude << "]";
Lorenz Meier's avatar
Lorenz Meier committed
2046 2047 2048
    }
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
2049 2050 2051 2052 2053 2054 2055 2056
        oss << " x = " << x <<
            " y = " << y <<
            " z = " << z <<
            " r = " << roll <<
            " p = " << pitch <<
            " y = " << yaw <<
            " Cursor [" << cursorPosition.x() <<
            " " << cursorPosition.y() << "]";
2057 2058
    }

2059
    mStatusText->setText(oss.str());
2060

2061
    bool darkBackground = true;
2062 2063
    if (frame == MAV_FRAME_GLOBAL &&
        mImageryNode->getImageryType() == Imagery::GOOGLE_MAP)
Lorenz Meier's avatar
Lorenz Meier committed
2064
    {
2065 2066 2067
        darkBackground = false;
    }

2068 2069 2070
    mScaleGeode->update(height(), m3DWidget->cameraParams().fov(),
                        m3DWidget->cameraManipulator()->getDistance(),
                        darkBackground);
2071 2072 2073
}

void
2074 2075
Pixhawk3DWidget::updateTrails(double robotX, double robotY, double robotZ,
                              osg::ref_ptr<osg::Geode>& trailNode,
2076
                              osg::ref_ptr<osg::Group>& orientationNode,
2077 2078
                              QMap<int, QVector<osg::Vec3d> >& trailMap,
                              QMap<int, int>& trailIndexMap)
2079
{
2080
    QMapIterator<int,int> it(trailIndexMap);
2081

2082
    while (it.hasNext())
Lorenz Meier's avatar
Lorenz Meier committed
2083
    {
2084
        it.next();
2085

2086 2087
        // update trail
        osg::Geometry* geometry = trailNode->getDrawable(it.value() * 2)->asGeometry();
2088 2089 2090 2091
        osg::DrawArrays* drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));

        osg::ref_ptr<osg::Vec3Array> vertices(new osg::Vec3Array);

2092
        const QVector<osg::Vec3d>& trail = trailMap.value(it.key());
2093

2094
        vertices->reserve(trail.size());
2095
        for (int i = 0; i < trail.size(); ++i)
Lorenz Meier's avatar
Lorenz Meier committed
2096
        {
2097 2098 2099
            vertices->push_back(osg::Vec3d(trail[i].y() - robotY,
                                           trail[i].x() - robotX,
                                           -(trail[i].z() - robotZ)));
2100 2101
        }

2102 2103 2104 2105
        geometry->setVertexArray(vertices);
        drawArrays->setFirst(0);
        drawArrays->setCount(vertices->size());
        geometry->dirtyBound();
2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137

        // update link
        geometry = trailNode->getDrawable(it.value() * 2 + 1)->asGeometry();
        drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));

        vertices = new osg::Vec3Array;

        if (!trail.empty())
        {
            QVector3D p(trail.back().x() - robotX,
                        trail.back().y() - robotY,
                        trail.back().z() - robotZ);

            double length = p.length();
            p.normalize();

            for (double i = 0.1; i < length - 0.1; i += 0.3)
            {
                QVector3D v = p * i;

                vertices->push_back(osg::Vec3d(v.y(), v.x(), -v.z()));
            }
        }
        if (vertices->size() % 2 == 1)
        {
            vertices->pop_back();
        }

        geometry->setVertexArray(vertices);
        drawArrays->setFirst(0);
        drawArrays->setCount(vertices->size());
        geometry->dirtyBound();
2138 2139 2140 2141 2142 2143 2144 2145 2146

        if (!trail.empty())
        {
            osg::PositionAttitudeTransform* pat =
                dynamic_cast<osg::PositionAttitudeTransform*>(orientationNode->getChild(it.value()));
            pat->setPosition(osg::Vec3(trail.back().y() - robotY,
                                       trail.back().x() - robotX,
                                       -(trail.back().z() - robotZ)));
        }
2147 2148 2149
    }
}

2150
void
2151 2152
Pixhawk3DWidget::updateImagery(double originX, double originY,
                               const QString& zone, MAV_FRAME frame)
2153
{
2154
    if (mImageryNode->getImageryType() == Imagery::BLANK_MAP)
Lorenz Meier's avatar
Lorenz Meier committed
2155
    {
2156 2157 2158
        return;
    }

2159
    double viewingRadius = m3DWidget->cameraManipulator()->getDistance() * 10.0;
2160
    if (viewingRadius < 200.0)
Lorenz Meier's avatar
Lorenz Meier committed
2161
    {
2162
        viewingRadius = 200.0;
2163 2164 2165
    }

    double minResolution = 0.25;
2166
    double centerResolution = m3DWidget->cameraManipulator()->getDistance() / 50.0;
2167 2168
    double maxResolution = 1048576.0;

2169
    Imagery::Type imageryType = mImageryNode->getImageryType();
Lorenz Meier's avatar
Lorenz Meier committed
2170 2171
    switch (imageryType)
    {
2172 2173 2174 2175 2176 2177
    case Imagery::GOOGLE_MAP:
        minResolution = 0.25;
        break;
    case Imagery::GOOGLE_SATELLITE:
        minResolution = 0.5;
        break;
2178
    case Imagery::OFFLINE_SATELLITE:
2179 2180
        minResolution = 0.5;
        maxResolution = 0.5;
2181
        break;
2182
    default:
2183
        {}
2184 2185 2186
    }

    double resolution = minResolution;
Lorenz Meier's avatar
Lorenz Meier committed
2187 2188
    while (resolution * 2.0 < centerResolution)
    {
2189 2190
        resolution *= 2.0;
    }
Lorenz Meier's avatar
Lorenz Meier committed
2191 2192 2193

    if (resolution > maxResolution)
    {
2194 2195 2196
        resolution = maxResolution;
    }

2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208
    double x = m3DWidget->cameraManipulator()->getCenter().y();
    double y = m3DWidget->cameraManipulator()->getCenter().x();

    double xOffset = 0.0;
    double yOffset = 0.0;

    if (frame == MAV_FRAME_LOCAL_NED)
    {
        xOffset = originX;
        yOffset = originY;
    }

2209 2210
    mImageryNode->draw3D(viewingRadius,
                         resolution,
2211 2212 2213 2214
                         x + xOffset,
                         y + yOffset,
                         -xOffset,
                         -yOffset,
2215
                         zone);
2216 2217

    // prefetch map tiles
Lorenz Meier's avatar
Lorenz Meier committed
2218 2219
    if (resolution / 2.0 >= minResolution)
    {
2220 2221
        mImageryNode->prefetch3D(viewingRadius / 2.0,
                                 resolution / 2.0,
2222 2223
                                 x + xOffset,
                                 y + yOffset,
2224
                                 zone);
2225
    }
Lorenz Meier's avatar
Lorenz Meier committed
2226 2227
    if (resolution * 2.0 <= maxResolution)
    {
2228 2229
        mImageryNode->prefetch3D(viewingRadius * 2.0,
                                 resolution * 2.0,
2230 2231
                                 x + xOffset,
                                 y + yOffset,
2232
                                 zone);
2233 2234
    }

2235
    mImageryNode->update();
2236
}
2237

2238
void
2239 2240 2241 2242
Pixhawk3DWidget::updateTarget(UASInterface* uas, MAV_FRAME frame,
                              double robotX, double robotY, double robotZ,
                              QVector4D& target,
                              osg::ref_ptr<osg::Node>& targetNode)
2243
{
2244 2245 2246
    Q_UNUSED(uas);
    Q_UNUSED(frame);

2247
    osg::PositionAttitudeTransform* pat =
2248 2249
        dynamic_cast<osg::PositionAttitudeTransform*>(targetNode.get());

2250 2251 2252 2253
    pat->setPosition(osg::Vec3d(target.y() - robotY,
                                target.x() - robotX,
                                -(target.z() - robotZ)));
    pat->setAttitude(osg::Quat(target.w() - M_PI_2, osg::Vec3d(1.0f, 0.0f, 0.0f),
2254 2255
                               M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f),
                               0.0, osg::Vec3d(0.0f, 0.0f, 1.0f)));
2256 2257
}

2258
void
2259 2260
Pixhawk3DWidget::updateWaypoints(UASInterface* uas, MAV_FRAME frame,
                                 osg::ref_ptr<WaypointGroupNode>& waypointGroupNode)
2261
{
2262
    waypointGroupNode->update(uas, frame);
2263
}
2264

2265
int
2266
Pixhawk3DWidget::findWaypoint(const QPoint& mousePos)
2267
{
2268
    if (!m3DWidget->getSceneData() || !mActiveUAS)
2269
    {
2270 2271
        return -1;
    }
2272

2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    osg::ref_ptr<WaypointGroupNode>& waypointGroupNode = systemData.waypointGroupNode();

    osgUtil::LineSegmentIntersector::Intersections intersections;

    QPoint widgetMousePos = m3DWidget->mapFromParent(mousePos);

    if (m3DWidget->computeIntersections(widgetMousePos.x(),
                                        m3DWidget->height() - widgetMousePos.y(),
                                        intersections))
    {
        for (osgUtil::LineSegmentIntersector::Intersections::iterator
             it = intersections.begin(); it != intersections.end(); it++)
2286
        {
2287
            for (uint i = 0 ; i < it->nodePath.size(); ++i)
2288
            {
2289 2290 2291
                osg::Node* node = it->nodePath[i];
                std::string nodeName = node->getName();
                if (nodeName.substr(0, 2).compare("wp") == 0)
2292
                {
2293
                    if (node->getParent(0)->getParent(0) == waypointGroupNode.get())
2294
                    {
2295
                        return atoi(nodeName.substr(2).c_str());
2296 2297 2298 2299 2300 2301 2302 2303 2304
                    }
                }
            }
        }
    }

    return -1;
}

2305

2306 2307 2308
bool
Pixhawk3DWidget::findTarget(int mouseX, int mouseY)
{
2309
    if (m3DWidget->getSceneData())
2310
    {
2311 2312
        osgUtil::LineSegmentIntersector::Intersections intersections;

2313
        if (m3DWidget->computeIntersections(mouseX, height() - mouseY, intersections))
2314
        {
2315
            for (osgUtil::LineSegmentIntersector::Intersections::iterator
2316 2317 2318 2319
                    it = intersections.begin(); it != intersections.end(); it++)
            {
                for (uint i = 0 ; i < it->nodePath.size(); ++i)
                {
2320
                    std::string nodeName = it->nodePath[i]->getName();
2321 2322
                    if (nodeName.compare("Target") == 0)
                    {
2323 2324 2325 2326 2327 2328 2329 2330 2331 2332
                        return true;
                    }
                }
            }
        }
    }

    return false;
}

2333 2334 2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346 2347 2348 2349 2350 2351 2352 2353 2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364 2365 2366 2367
bool
Pixhawk3DWidget::findTerrain(const QPoint& mousePos)
{
    if (!m3DWidget->getSceneData() || !mActiveUAS)
    {
        return -1;
    }

    osgUtil::LineSegmentIntersector::Intersections intersections;

    QPoint widgetMousePos = m3DWidget->mapFromParent(mousePos);

    if (m3DWidget->computeIntersections(widgetMousePos.x(),
                                        m3DWidget->height() - widgetMousePos.y(),
                                        intersections))
    {
        for (osgUtil::LineSegmentIntersector::Intersections::iterator
             it = intersections.begin(); it != intersections.end(); it++)
        {
            for (uint i = 0 ; i < it->nodePath.size(); ++i)
            {
                osg::Node* node = it->nodePath[i];
                std::string nodeName = node->getName();

                if (nodeName.compare("terrain") == 0)
                {
                    return true;
                }
            }
        }
    }

    return false;
}

2368 2369 2370 2371 2372 2373
void
Pixhawk3DWidget::showInsertWaypointMenu(const QPoint &cursorPos)
{
    QMenu menu;
    menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
2374
    menu.addAction("Select target", this, SLOT(selectTarget()));
2375 2376 2377 2378 2379 2380 2381 2382 2383
    menu.exec(cursorPos);
}

void
Pixhawk3DWidget::showEditWaypointMenu(const QPoint &cursorPos)
{
    QMenu menu;

    QString text;
2384
    text = QString("Move waypoint %1").arg(QString::number(mSelectedWpIndex));
2385 2386
    menu.addAction(text, this, SLOT(moveWaypointPosition()));

2387
    text = QString("Change heading of waypoint %1").arg(QString::number(mSelectedWpIndex));
2388
    menu.addAction(text, this, SLOT(moveWaypointHeading()));
2389

2390
    text = QString("Change altitude of waypoint %1").arg(QString::number(mSelectedWpIndex));
2391 2392
    menu.addAction(text, this, SLOT(setWaypointAltitude()));

2393
    text = QString("Delete waypoint %1").arg(QString::number(mSelectedWpIndex));
2394 2395 2396 2397 2398
    menu.addAction(text, this, SLOT(deleteWaypoint()));

    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
    menu.exec(cursorPos);
}
2399 2400 2401 2402 2403 2404 2405 2406

void
Pixhawk3DWidget::showTerrainMenu(const QPoint &cursorPos)
{
    QMenu menu;
    menu.addAction("Edit terrain parameters", this, SLOT(showTerrainParamWindow()));
    menu.exec(cursorPos);
}