Pixhawk3DWidget.cc 86.8 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"
48

49
#include "QGC.h"
50
#include "gpl.h"
51

52
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
53
#include <tr1/memory>
LM's avatar
LM committed
54
#include <pixhawk/pixhawk.pb.h>
55 56
#endif

57
Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
58 59 60 61 62 63 64 65 66 67
 : 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))
68
{
69
    connect(m3DWidget, SIGNAL(sizeChanged(int,int)), this, SLOT(sizeChanged(int,int)));
70
    connect(m3DWidget, SIGNAL(updateWidget()), this, SLOT(updateWidget()));
71

72 73 74
    m3DWidget->setCameraParams(2.0f, 30.0f, 0.01f, 10000.0f);
    m3DWidget->init(15.0f);
    m3DWidget->handleDeviceEvents() = false;
75

76 77
    mWorldGridNode = createWorldGrid();
    m3DWidget->worldMap()->addChild(mWorldGridNode, false);
78

79 80 81
    mTerrainPAT = new osg::PositionAttitudeTransform;
    m3DWidget->worldMap()->addChild(mTerrainPAT);

82
    // generate map model
83
    mImageryNode = createImagery();
84
    mImageryNode->setName("imagery");
85
    m3DWidget->worldMap()->addChild(mImageryNode, false);
86

87
    setupHUD();
88

89
    buildLayout();
90

91 92 93 94 95 96
    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)));
97 98
    connect(mGlobalViewParams.data(), SIGNAL(imageryParamsChanged(void)),
            this, SLOT(imageryParamsChanged(void)));
99

100 101
    MainWindow* parentWindow = qobject_cast<MainWindow*>(parent);
    parentWindow->addDockWidget(Qt::LeftDockWidgetArea, mViewParamWidget);
102

103
    mViewParamWidget->hide();
104

105 106 107
    setFocusPolicy(Qt::StrongFocus);
    setMouseTracking(true);
}
108

109 110
Pixhawk3DWidget::~Pixhawk3DWidget()
{
111

112 113
}

114 115
void
Pixhawk3DWidget::activeSystemChanged(UASInterface* uas)
116
{
117 118 119 120
    if (uas)
    {
        mActiveSystemId = uas->getUASID();
    }
121 122

    mActiveUAS = uas;
123

124
    mMode = DEFAULT_MODE;
125 126
}

127
void
128
Pixhawk3DWidget::systemCreated(UASInterface *uas)
129
{
130 131 132
    int systemId = uas->getUASID();

    if (mSystemContainerMap.contains(systemId))
133 134 135 136
    {
        return;
    }

137 138
    mSystemViewParamMap.insert(systemId, SystemViewParamsPtr(new SystemViewParams(systemId)));
    mSystemContainerMap.insert(systemId, SystemContainer());
139

140 141
    connect(uas, SIGNAL(localPositionChanged(UASInterface*,int,double,double,double,quint64)),
            this, SLOT(localPositionChanged(UASInterface*,int,double,double,double,quint64)));
142 143
    connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)),
            this, SLOT(localPositionChanged(UASInterface*,double,double,double,quint64)));
144 145
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)),
            this, SLOT(attitudeChanged(UASInterface*,int,double,double,double,quint64)));
146 147 148 149
    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)));
150 151
    connect(uas, SIGNAL(homePositionChanged(int,double,double,double)),
            this, SLOT(homePositionChanged(int,double,double,double)));
152 153 154 155
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
    connect(uas, SIGNAL(overlayChanged(UASInterface*)),
            this, SLOT(addOverlay(UASInterface*)));
#endif
156

157
//    mSystemContainerMap[systemId].gpsLocalOrigin() = QVector3D(47.397786, 8.544476, 428);
158
    initializeSystem(systemId, uas->getColor());
159

160
    emit systemCreatedSignal(uas);
161 162
}

163
void
164 165 166
Pixhawk3DWidget::localPositionChanged(UASInterface* uas, int component,
                                      double x, double y, double z,
                                      quint64 time)
167
{
168 169
    Q_UNUSED(time);

170 171 172
    int systemId = uas->getUASID();

    if (!mSystemContainerMap.contains(systemId))
173 174 175 176
    {
        return;
    }

177 178 179 180
    SystemContainer& systemData = mSystemContainerMap[systemId];

    // update trail data
    if (!systemData.trailMap().contains(component))
181
    {
182 183 184 185
        systemData.trailMap().insert(component, QVector<osg::Vec3d>());
        systemData.trailMap()[component].reserve(10000);
        systemData.trailIndexMap().insert(component,
                                          systemData.trailMap().size() - 1);
186

hengli's avatar
hengli committed
187 188 189 190 191 192 193 194 195 196 197 198 199 200 201
        // 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());
202

203
        systemData.trailNode()->addDrawable(createTrail(color));
204
        systemData.trailNode()->addDrawable(createLink(uas->getColor()));
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 238 239 240 241 242 243 244 245

        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);

246
        // text indicates component id
247 248 249
        colorRGB.lighter();
        color = osg::Vec4(colorRGB.redF(), colorRGB.greenF(), colorRGB.blueF(), 1.0f);

250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271
        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);

272 273 274
        pat = new osg::PositionAttitudeTransform;
        pat->addChild(group);
        systemData.orientationNode()->addChild(pat);
275 276
    }

277
    QVector<osg::Vec3d>& trail = systemData.trailMap()[component];
278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309

    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);
        }
    }
}

310
void
311 312 313 314
Pixhawk3DWidget::localPositionChanged(UASInterface* uas,
                                      double x, double y, double z,
                                      quint64 time)
{
315 316
    Q_UNUSED(time);

317 318 319 320 321 322 323
    int systemId = uas->getUASID();

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

324 325
//    // Add offset
//    UAS* mav = qobject_cast<UAS*>(uas);
326

327 328 329 330
//    float offX = mav->getNedPosGlobalOffset().x();
//    float offY = mav->getNedPosGlobalOffset().y();
//    float offZ = mav->getNedPosGlobalOffset().z();
//    float offYaw = mav->getNedAttGlobalOffset().z();
331

332 333 334 335
    // update system position
    m3DWidget->systemGroup(systemId)->position()->setPosition(osg::Vec3d(y, x, -z));
}

336 337 338 339 340
void
Pixhawk3DWidget::attitudeChanged(UASInterface* uas, int component,
                                 double roll, double pitch, double yaw,
                                 quint64 time)
{
341 342 343 344
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(time);

345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369
    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)));
}

370 371
void
Pixhawk3DWidget::attitudeChanged(UASInterface* uas,
372 373
                                 double roll, double pitch, double yaw,
                                 quint64 time)
374
{
375 376
    Q_UNUSED(time);

377
    int systemId = uas->getUASID();
378

379
    if (!mSystemContainerMap.contains(systemId))
380 381 382 383
    {
        return;
    }

384 385 386 387 388
    // 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);
389 390
}

391 392 393 394 395 396 397 398 399 400 401 402 403 404
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);
}

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 435 436 437 438 439 440 441 442
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);
443
    if (setpointGroupNode->getNumChildren() > static_cast<unsigned int>(systemViewParams->setpointHistoryLength()))
444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464
    {
        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);
    }
}

465 466 467 468 469 470 471 472 473 474 475 476 477 478
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
479 480
        systemData.orientationNode()->removeChildren(0, systemData.orientationNode()->getNumChildren());
        systemData.trailIndexMap().clear();
481
        systemData.trailMap().clear();
482
        systemData.trailNode()->removeDrawables(0, systemData.trailNode()->getNumDrawables());
483 484 485
    }
}

486 487 488 489 490
void
Pixhawk3DWidget::showTerrainParamWindow(void)
{
    TerrainParamDialog::getTerrainParams(mGlobalViewParams);

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

494
    mTerrainPAT->setPosition(osg::Vec3d(positionOffset.y(), positionOffset.x(), -positionOffset.z()));
495
    mTerrainPAT->setAttitude(osg::Quat(- attitudeOffset.z(), osg::Vec3d(0.0f, 0.0f, 1.0f),
496 497
                                       attitudeOffset.y(), osg::Vec3d(1.0f, 0.0f, 0.0f),
                                       attitudeOffset.x(), osg::Vec3d(0.0f, 1.0f, 0.0f)));
498 499
}

500
void
501
Pixhawk3DWidget::showViewParamWindow(void)
502
{
503 504 505 506 507
    if (mViewParamWidget->isVisible())
    {
        mViewParamWidget->hide();
    }
    else
508
    {
509
        mViewParamWidget->show();
510
    }
511 512
}

513
void
514
Pixhawk3DWidget::followCameraChanged(int systemId)
515
{
516
    if (systemId == -1)
517
    {
518
        mFollowCameraId = -1;
519 520
    }

521 522
    UASInterface* uas = UASManager::instance()->getUASForId(systemId);
    if (!uas)
523
    {
524
        return;
525
    }
526 527

    if (mFollowCameraId != systemId)
528
    {
529 530 531 532 533 534 535 536
        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;
537 538 539
    }
}

540 541 542 543 544 545 546 547 548 549
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());
}

550
void
551
Pixhawk3DWidget::recenterActiveCamera(void)
552
{
553
    if (mFollowCameraId != -1)
554
    {
555 556
        UASInterface* uas = UASManager::instance()->getUASForId(mFollowCameraId);
        if (!uas)
557
        {
558
            return;
559 560
        }

561 562
        double x = 0.0, y = 0.0, z = 0.0;
        getPosition(uas, mGlobalViewParams->frame(), x, y, z);
563

564 565 566
        mCameraPos = QVector3D(x, y, z);

        m3DWidget->recenterCamera(y, x, -z);
567 568 569
    }
}

570
void
571
Pixhawk3DWidget::modelChanged(int systemId, int index)
572
{
573
    if (!mSystemContainerMap.contains(systemId))
574
    {
575
        return;
576
    }
577

578 579 580 581 582 583
    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());
584 585
}

586
void
587
Pixhawk3DWidget::setBirdEyeView(void)
588
{
589
    mViewParamWidget->setFollowCameraId(-1);
590

591
    m3DWidget->rotateCamera(0.0, 0.0, 0.0);
592
    m3DWidget->setCameraDistance(100.0);
593
}
594

595 596 597
void
Pixhawk3DWidget::loadTerrainModel(void)
{
Don Gagne's avatar
Don Gagne committed
598
    QString filename = QGCFileDialog::getOpenFileName(this, "Load Terrain Model",
599
                                                    QStandardPaths::writableLocation(QStandardPaths::DesktopLocation),
600 601 602 603 604 605 606 607 608 609 610 611 612 613
                                                    tr("Collada (*.dae)"));

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

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

    if (node)
    {
        if (mTerrainNode.get())
        {
614
            mTerrainPAT->removeChild(mTerrainNode);
615 616
        }
        mTerrainNode = node;
617 618 619
        mTerrainNode->setName("terrain");
        mTerrainPAT->addChild(mTerrainNode);

620 621
        mGlobalViewParams->terrainPositionOffset() = QVector3D();
        mGlobalViewParams->terrainAttitudeOffset() = QVector3D();
622 623

        mTerrainPAT->setPosition(osg::Vec3d(0.0, 0.0, 0.0));
624
        mTerrainPAT->setAttitude(osg::Quat(0.0, osg::Vec3d(0.0f, 0.0f, 1.0f),
625 626
                                           0.0, osg::Vec3d(1.0f, 0.0f, 0.0f),
                                           0.0, osg::Vec3d(0.0f, 1.0f, 0.0f)));
627 628 629 630 631 632 633 634 635 636
    }
    else
    {
        QMessageBox msgBox(QMessageBox::Warning,
                           "Error loading model",
                           QString("Error: Unable to load terrain model (%1).").arg(filename));
        msgBox.exec();
    }
}

637 638 639 640 641 642 643 644 645 646 647 648 649
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
void
Pixhawk3DWidget::addOverlay(UASInterface *uas)
{
    int systemId = uas->getUASID();

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

    SystemContainer& systemData = mSystemContainerMap[systemId];

650 651
    qreal receivedTimestamp;
    px::GLOverlay overlay = uas->getOverlay(receivedTimestamp);
652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667

    QString overlayName = QString::fromStdString(overlay.name());

    osg::ref_ptr<SystemGroupNode>& systemNode = m3DWidget->systemGroup(systemId);

    if (!systemData.overlayNodeMap().contains(overlayName))
    {
        osg::ref_ptr<GLOverlayGeode> overlayNode = new GLOverlayGeode;
        systemData.overlayNodeMap().insert(overlayName, overlayNode);

        systemNode->allocentricMap()->addChild(overlayNode, false);
        systemNode->rollingMap()->addChild(overlayNode, false);

        emit overlayCreatedSignal(systemId, overlayName);
    }

668 669 670
    osg::ref_ptr<GLOverlayGeode>& overlayNode = systemData.overlayNodeMap()[overlayName];
    overlayNode->setOverlay(overlay);
    overlayNode->setMessageTimestamp(receivedTimestamp);
671 672 673
}
#endif

674
void
675
Pixhawk3DWidget::selectTargetHeading(void)
676
{
677
    if (!mActiveUAS)
678 679 680
    {
        return;
    }
681

682 683
    osg::Vec2d p;

684
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
685
    {
686
        double altitude = mActiveUAS->getAltitudeAMSL();
687

688 689
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), altitude);
690

691
        p.set(cursorWorldCoords.x(), cursorWorldCoords.y());
692
    }
693
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
694
    {
695
        double z = mActiveUAS->getLocalZ();
696

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

700
        p.set(cursorWorldCoords.x(), cursorWorldCoords.y());
701
    }
702

703 704 705
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

706
    target.setW(atan2(p.y() - target.y(), p.x() - target.x()));
707 708 709 710 711
}

void
Pixhawk3DWidget::selectTarget(void)
{
712
    if (!mActiveUAS)
713 714 715
    {
        return;
    }
716
    if (!mActiveUAS->getParamManager())
717 718 719
    {
        return;
    }
720

721 722 723 724
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
725
    {
726
        double altitude = mActiveUAS->getAltitudeAMSL();
727

728 729
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, altitude);
730

731
        QVariant zTarget;
732
        if (!mActiveUAS->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
733 734 735 736
        {
            zTarget = -altitude;
        }

737
        target = QVector4D(cursorWorldCoords.x(), cursorWorldCoords.y(),
738
                           zTarget.toReal(), 0.0);
739
    }
740
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
741
    {
742
        double z = mActiveUAS->getLocalZ();
743

744 745
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, -z);
746

747
        QVariant zTarget;
748
        if (!mActiveUAS->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
749 750 751 752
        {
            zTarget = z;
        }

753
        target = QVector4D(cursorWorldCoords.x(), cursorWorldCoords.y(),
754
                           zTarget.toReal(), 0.0);
755
    }
756

757
    int systemId = mActiveUAS->getUASID();
758

759 760 761 762 763 764 765
    QMap<int, SystemViewParamsPtr>::iterator it = mSystemViewParamMap.find(systemId);
    if (it != mSystemViewParamMap.end())
    {
        it.value()->displayTarget() = true;
    }

    mMode = SELECT_TARGET_HEADING_MODE;
766 767 768 769 770 771 772
}

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

773 774 775 776 777
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

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

780 781 782
void
Pixhawk3DWidget::insertWaypoint(void)
{
783
    if (!mActiveUAS)
784 785 786
    {
        return;
    }
787

788
    Waypoint* wp = NULL;
789
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
790
    {
791 792
        double latitude = mActiveUAS->getLatitude();
        double longitude = mActiveUAS->getLongitude();
793
        double altitude = mActiveUAS->getAltitudeAMSL();
794 795 796 797
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

798 799
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, altitude);
800

801
        Imagery::UTMtoLL(cursorWorldCoords.x(), cursorWorldCoords.y(), utmZone,
802 803
                         latitude, longitude);

804
        wp = new Waypoint(0, longitude, latitude, altitude, 0.0, 0.25);
805
    }
806
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
807
    {
808
        double z = mActiveUAS->getLocalZ();
809

810 811
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, -z);
812

813 814
        wp = new Waypoint(0, cursorWorldCoords.x(),
                          cursorWorldCoords.y(), z, 0.0, 0.25);
815 816 817 818
    }

    if (wp)
    {
819 820
        wp->setFrame(mGlobalViewParams->frame());
        mActiveUAS->getWaypointManager()->addWaypointEditable(wp);
821 822
    }

823 824
    mSelectedWpIndex = wp->getId();
    mMode = MOVE_WAYPOINT_HEADING_MODE;
825 826 827
}

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

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

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

845
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
846
    {
847 848
        double latitude = mActiveUAS->getLatitude();
        double longitude = mActiveUAS->getLongitude();
849
        double altitude = mActiveUAS->getAltitudeAMSL();
850 851 852 853
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

854 855
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), altitude);
856

857
        Imagery::UTMtoLL(cursorWorldCoords.x(), cursorWorldCoords.y(),
858
                         utmZone, latitude, longitude);
859 860 861 862

        waypoint->setX(longitude);
        waypoint->setY(latitude);
    }
863
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
864
    {
865
        double z = mActiveUAS->getLocalZ();
866

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

870 871
        waypoint->setX(cursorWorldCoords.x());
        waypoint->setY(cursorWorldCoords.y());
872 873 874
    }
}

875 876 877
void
Pixhawk3DWidget::moveWaypointHeading(void)
{
878
    if (mMode != MOVE_WAYPOINT_HEADING_MODE)
879
    {
880
        mMode = MOVE_WAYPOINT_HEADING_MODE;
881 882 883
        return;
    }

884
    if (!mActiveUAS)
885 886 887 888
    {
        return;
    }

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

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

895
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
896 897 898 899 900 901 902
    {
        double latitude = waypoint->getY();
        double longitude = waypoint->getX();
        z = -waypoint->getZ();
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
    }
903
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
904
    {
905
        z = mActiveUAS->getLocalZ();
906 907
    }

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

911 912
    double yaw = atan2(cursorWorldCoords.y() - waypoint->getY(),
                       cursorWorldCoords.x() - waypoint->getX());
913 914 915 916 917
    yaw = osg::RadiansToDegrees(yaw);

    waypoint->setYaw(yaw);
}

918 919 920
void
Pixhawk3DWidget::deleteWaypoint(void)
{
921
    if (mActiveUAS)
922
    {
923
        mActiveUAS->getWaypointManager()->removeWaypoint(mSelectedWpIndex);
924 925 926 927 928 929
    }
}

void
Pixhawk3DWidget::setWaypointAltitude(void)
{
930
    if (!mActiveUAS)
931 932 933
    {
        return;
    }
934

935
    bool ok;
936
    const QList<Waypoint *> waypoints =
937 938
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
939

940
    double altitude = waypoint->getZ();
941
    if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
942 943 944 945 946
    {
        altitude = -altitude;
    }

    double newAltitude =
947
        QInputDialog::getDouble(this, tr("Set altitude of waypoint %1").arg(mSelectedWpIndex),
948 949 950
                                tr("Altitude (m):"), waypoint->getZ(), -1000.0, 1000.0, 1, &ok);
    if (ok)
    {
951
        if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
952 953 954
        {
            waypoint->setZ(newAltitude);
        }
955
        else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
956 957
        {
            waypoint->setZ(-newAltitude);
958
        }
959 960 961 962 963 964
    }
}

void
Pixhawk3DWidget::clearAllWaypoints(void)
{
965
    if (mActiveUAS)
966
    {
967
        const QList<Waypoint *> waypoints =
968
            mActiveUAS->getWaypointManager()->getWaypointEditableList();
969 970
        for (int i = waypoints.size() - 1; i >= 0; --i)
        {
971
            mActiveUAS->getWaypointManager()->removeWaypoint(i);
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 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074
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)));
}

1075 1076 1077 1078 1079 1080 1081
void
Pixhawk3DWidget::sizeChanged(int width, int height)
{
    resizeHUD(width, height);
}

void
1082
Pixhawk3DWidget::updateWidget(void)
1083 1084 1085 1086
{
    MAV_FRAME frame = mGlobalViewParams->frame();

    // set node visibility
1087
    m3DWidget->worldMap()->setChildValue(mTerrainPAT,
1088
                                         mGlobalViewParams->displayTerrain());
1089
    m3DWidget->worldMap()->setChildValue(mWorldGridNode,
1090
                                         mGlobalViewParams->displayWorldGrid());
1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109
    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();

1110 1111 1112 1113
        osg::ref_ptr<osg::Switch>& allocentricMap = systemNode->allocentricMap();
        allocentricMap->setChildValue(systemData.setpointGroupNode(),
                                      systemViewParams->displaySetpoints());

1114 1115 1116
        osg::ref_ptr<osg::Switch>& rollingMap = systemNode->rollingMap();
        rollingMap->setChildValue(systemData.localGridNode(),
                                  systemViewParams->displayLocalGrid());
1117 1118
        rollingMap->setChildValue(systemData.orientationNode(),
                                  systemViewParams->displayTrails());
1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130
        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 defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
        rollingMap->setChildValue(systemData.obstacleGroupNode(),
                                  systemViewParams->displayObstacleList());
1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141

        QMutableMapIterator<QString, osg::ref_ptr<GLOverlayGeode> > itOverlay(systemData.overlayNodeMap());
        while (itOverlay.hasNext())
        {
            itOverlay.next();

            osg::ref_ptr<GLOverlayGeode>& overlayNode = itOverlay.value();

            bool displayOverlay = systemViewParams->displayOverlay().value(itOverlay.key());

            bool visible;
1142 1143 1144
            visible = (overlayNode->coordinateFrameType() == px::GLOverlay::GLOBAL) &&
                      displayOverlay &&
                      (QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout);
1145 1146 1147

            allocentricMap->setChildValue(overlayNode, visible);

1148 1149 1150
            visible = (overlayNode->coordinateFrameType() == px::GLOverlay::LOCAL) &&
                      displayOverlay &&
                      (QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout);;
1151 1152 1153 1154

            rollingMap->setChildValue(overlayNode, visible);
        }

1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191
        rollingMap->setChildValue(systemData.plannedPathNode(),
                                  systemViewParams->displayPlannedPath());

        m3DWidget->hudGroup()->setChildValue(systemData.depthImageNode(),
                                             systemViewParams->displayRGBD());
        m3DWidget->hudGroup()->setChildValue(systemData.rgbImageNode(),
                                             systemViewParams->displayRGBD());
#endif
    }

    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);

1192
            setBirdEyeView();
1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218
            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);

1219 1220 1221 1222 1223 1224 1225 1226
        if (systemViewParams->displaySetpoints())
        {

        }
        else
        {
            systemData.setpointGroupNode()->removeChildren(0, systemData.setpointGroupNode()->getNumChildren());
        }
1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240
        if (systemViewParams->displayTarget())
        {
            if (systemData.target().isNull())
            {
                systemViewParams->displayTarget() = false;
            }
            else
            {
                updateTarget(uas, frame, x, y, z, systemData.target(),
                             systemData.targetNode());
            }
        }
        if (systemViewParams->displayTrails())
        {
1241
            updateTrails(x, y, z, systemData.trailNode(), systemData.orientationNode(),
1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271
                         systemData.trailMap(), systemData.trailIndexMap());
        }
        else
        {
            systemData.trailMap().clear();
        }
        if (systemViewParams->displayWaypoints())
        {
            updateWaypoints(uas, frame, systemData.waypointGroupNode());
        }

#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
        if (systemViewParams->displayObstacleList())
        {
            updateObstacles(uas, frame, x, y, z, systemData.obstacleGroupNode());
        }
        if (systemViewParams->displayPlannedPath())
        {
            updatePlannedPath(uas, frame, x, y, z, systemData.plannedPathNode());
        }
        if (systemViewParams->displayPointCloud())
        {
            updatePointCloud(uas, frame, x, y, z, systemData.pointCloudNode(),
                             systemViewParams->colorPointCloudByDistance());
        }
        if (systemViewParams->displayRGBD())
        {
            updateRGBD(uas, frame, systemData.rgbImageNode(),
                       systemData.depthImageNode());
        }
1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285

        if (frame == MAV_FRAME_LOCAL_NED &&
            mGlobalViewParams->imageryType() != Imagery::BLANK_MAP &&
            !systemData.gpsLocalOrigin().isNull() &&
            mActiveUAS->getUASID() == systemId)
        {
            const QVector3D& gpsLocalOrigin = systemData.gpsLocalOrigin();

            double utmX, utmY;
            QString utmZone;
            Imagery::LLtoUTM(gpsLocalOrigin.x(), gpsLocalOrigin.y(), utmX, utmY, utmZone);

            updateImagery(utmX, utmY, utmZone, frame);
        }
1286 1287 1288 1289 1290 1291
#endif
    }

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

1295 1296 1297 1298
    if (mActiveUAS)
    {
      updateHUD(mActiveUAS, frame);
    }
1299 1300 1301 1302 1303 1304 1305

    layout()->update();
}

void
Pixhawk3DWidget::addModels(QVector< osg::ref_ptr<osg::Node> >& models,
                           const QColor& systemColor)
1306 1307
{
    QDir directory("models");
lm's avatar
lm committed
1308
    QStringList files = directory.entryList(QStringList("*.osg"), QDir::Files);
1309 1310

    // add Pixhawk Bravo model
1311
    models.push_back(PixhawkCheetahNode::create(systemColor));
1312

hengli's avatar
hengli committed
1313 1314 1315
    // 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);
1316
    sphereDrawable->setColor(osg::Vec4f(systemColor.redF(), systemColor.greenF(), systemColor.blueF(), 1.0f));
hengli's avatar
hengli committed
1317 1318 1319
    osg::ref_ptr<osg::Geode> sphereGeode = new osg::Geode;
    sphereGeode->addDrawable(sphereDrawable);
    sphereGeode->setName("Sphere (0.1m)");
1320
    models.push_back(sphereGeode);
hengli's avatar
hengli committed
1321

1322
    // add all other models in folder
1323 1324
    for (int i = 0; i < files.size(); ++i)
    {
1325
        osg::ref_ptr<osg::Node> node =
1326
            osgDB::readNodeFile(directory.absoluteFilePath(files[i]).toStdString().c_str());
1327

1328 1329
        if (node)
        {
1330
            models.push_back(node);
1331 1332 1333
        }
        else
        {
1334
            printf("%s\n", QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
lm's avatar
lm committed
1335
        }
1336 1337 1338 1339 1340 1341
    }
}

void
Pixhawk3DWidget::buildLayout(void)
{
1342 1343 1344
    QPushButton* clearDataButton = new QPushButton(this);
    clearDataButton->setText("Clear Data");

1345
    QPushButton* viewParamWindowButton = new QPushButton(this);
1346
    viewParamWindowButton->setCheckable(true);
1347
    viewParamWindowButton->setText("View Parameters");
1348

1349 1350
    QHBoxLayout* layoutTop = new QHBoxLayout;
    layoutTop->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding));
1351
    layoutTop->addWidget(clearDataButton);
1352
    layoutTop->addWidget(viewParamWindowButton);
1353 1354 1355 1356

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

1357 1358
    QPushButton* birdEyeViewButton = new QPushButton(this);
    birdEyeViewButton->setText("Bird's Eye View");
1359

1360 1361 1362
    QPushButton* loadTerrainModelButton = new QPushButton(this);
    loadTerrainModelButton->setText("Load Terrain Model");

1363 1364
    QHBoxLayout* layoutBottom = new QHBoxLayout;
    layoutBottom->addWidget(recenterButton);
1365
    layoutBottom->addWidget(birdEyeViewButton);
1366
    layoutBottom->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding));
1367
    layoutBottom->addWidget(loadTerrainModelButton);
1368 1369 1370 1371

    QGridLayout* layout = new QGridLayout(this);
    layout->setMargin(0);
    layout->setSpacing(2);
1372 1373 1374
    layout->addLayout(layoutTop, 0, 0);
    layout->addWidget(m3DWidget, 1, 0);
    layout->addLayout(layoutBottom, 2, 0);
1375 1376 1377
    layout->setRowStretch(0, 1);
    layout->setRowStretch(1, 100);
    layout->setRowStretch(2, 1);
1378

1379 1380
    connect(clearDataButton, SIGNAL(clicked()),
            this, SLOT(clearData()));
1381 1382 1383 1384
    connect(viewParamWindowButton, SIGNAL(clicked()),
            this, SLOT(showViewParamWindow()));
    connect(recenterButton, SIGNAL(clicked()),
            this, SLOT(recenterActiveCamera()));
1385 1386
    connect(birdEyeViewButton, SIGNAL(clicked()),
            this, SLOT(setBirdEyeView()));
1387 1388
    connect(loadTerrainModelButton, SIGNAL(clicked()),
            this, SLOT(loadTerrainModel()));
1389 1390
}

1391
void
1392
Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
1393
{
1394 1395
    QWidget::keyPressEvent(event);
    if (event->isAccepted())
1396
    {
1397 1398 1399
        return;
    }

1400
    m3DWidget->handleKeyPressEvent(event);
1401 1402
}

1403
void
1404
Pixhawk3DWidget::keyReleaseEvent(QKeyEvent* event)
1405
{
1406 1407
    QWidget::keyReleaseEvent(event);
    if (event->isAccepted())
1408
    {
1409
        return;
1410 1411
    }

1412
    m3DWidget->handleKeyReleaseEvent(event);
1413 1414
}

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

1424 1425
    if (event->button() == Qt::LeftButton)
    {
1426
        if (mMode == SELECT_TARGET_HEADING_MODE)
1427
        {
1428
            setTarget();
1429
            event->accept();
1430 1431
        }

1432
        if (mMode != DEFAULT_MODE)
1433
        {
1434 1435
            mMode = DEFAULT_MODE;
            event->accept();
1436
        }
1437 1438 1439 1440
    }
    else if (event->button() == Qt::RightButton)
    {
        if (m3DWidget->getSceneData() && mActiveUAS)
1441
        {
1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484
            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;
1485
            if (mSelectedWpIndex == -1)
1486
            {
1487
                mCachedMousePos = event->pos();
1488

1489
                menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
1490 1491 1492
            }
            else
            {
1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504
                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()));
1505 1506
            }

1507
            menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
1508
            menu.addSeparator();
1509 1510 1511 1512
            menu.addAction("Select target", this, SLOT(selectTarget()));

            if (mouseOverImagery)
            {
1513
                menu.addSeparator();
1514 1515 1516 1517
                menu.addAction("Move imagery", this, SLOT(moveImagery()));
            }
            if (mouseOverTerrain)
            {
1518
                menu.addSeparator();
1519 1520 1521 1522 1523 1524
                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());
1525 1526 1527 1528 1529

            event->accept();
        }
    }

1530

1531
    m3DWidget->handleMousePressEvent(event);
1532 1533
}

1534
void
1535
Pixhawk3DWidget::mouseReleaseEvent(QMouseEvent* event)
1536
{
1537 1538 1539 1540 1541
    QWidget::mouseReleaseEvent(event);
    if (event->isAccepted())
    {
        return;
    }
1542

1543
    m3DWidget->handleMouseReleaseEvent(event);
1544 1545
}

1546 1547 1548
void
Pixhawk3DWidget::mouseMoveEvent(QMouseEvent* event)
{
1549 1550 1551 1552 1553 1554
    QWidget::mouseMoveEvent(event);
    if (event->isAccepted())
    {
        return;
    }

1555
    switch (mMode)
1556
    {
1557
    case SELECT_TARGET_HEADING_MODE:
1558
        selectTargetHeading();
1559
        event->accept();
1560 1561
        break;
    case MOVE_WAYPOINT_POSITION_MODE:
1562
        moveWaypointPosition();
1563
        event->accept();
1564 1565
        break;
    case MOVE_WAYPOINT_HEADING_MODE:
1566
        moveWaypointHeading();
1567
        event->accept();
1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582
        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:
        {}
1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602
    }

    m3DWidget->handleMouseMoveEvent(event);
}

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

    m3DWidget->handleWheelEvent(event);
}

void
Pixhawk3DWidget::showEvent(QShowEvent* event)
{
1603 1604
    Q_UNUSED(event);

1605 1606 1607 1608 1609 1610
    emit visibilityChanged(true);
}

void
Pixhawk3DWidget::hideEvent(QHideEvent* event)
{
1611 1612
    Q_UNUSED(event);

1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626
    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);

1627 1628 1629 1630
    // generate orientation model
    systemData.orientationNode() = new osg::Group;
    systemNode->rollingMap()->addChild(systemData.orientationNode(), false);

1631 1632 1633 1634
    // generate point cloud model
    systemData.pointCloudNode() = createPointCloud();
    systemNode->rollingMap()->addChild(systemData.pointCloudNode(), false);

1635 1636 1637 1638
    // generate setpoint model
    systemData.setpointGroupNode() = new osg::Group;
    systemNode->allocentricMap()->addChild(systemData.setpointGroupNode(), false);

1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678
    // 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);

#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
    systemData.obstacleGroupNode() = new ObstacleGroupNode;
    systemData.obstacleGroupNode()->init();
    systemNode->rollingMap()->addChild(systemData.obstacleGroupNode(), false);

    // generate path model
    systemData.plannedPathNode() = new osg::Geode;
    systemData.plannedPathNode()->addDrawable(createTrail(osg::Vec4(1.0f, 0.8f, 0.0f, 1.0f)));
    systemNode->rollingMap()->addChild(systemData.plannedPathNode(), false);
#endif

    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());
1679
    }
1680

1681 1682 1683 1684 1685
    systemData.modelNode() = systemData.models().front();
    systemNode->egocentricMap()->addChild(systemData.modelNode());

    connect(systemViewParams.data(), SIGNAL(modelChangedSignal(int,int)),
            this, SLOT(modelChanged(int,int)));
1686 1687
}

1688
void
1689 1690 1691
Pixhawk3DWidget::getPose(UASInterface* uas,
                         MAV_FRAME frame,
                         double& x, double& y, double& z,
1692
                         double& roll, double& pitch, double& yaw,
1693
                         QString& utmZone) const
1694
{
1695 1696 1697 1698
    if (!uas)
    {
        return;
    }
1699

1700 1701 1702 1703
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
1704
        double altitude = uas->getAltitudeAMSL();
1705 1706 1707

        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
        z = -altitude;
1708
    }
1709 1710 1711 1712 1713
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
        x = uas->getLocalX();
        y = uas->getLocalY();
        z = uas->getLocalZ();
1714
    }
1715 1716 1717 1718

    roll = uas->getRoll();
    pitch = uas->getPitch();
    yaw = uas->getYaw();
1719 1720 1721
}

void
1722 1723 1724 1725
Pixhawk3DWidget::getPose(UASInterface* uas,
                         MAV_FRAME frame,
                         double& x, double& y, double& z,
                         double& roll, double& pitch, double& yaw) const
1726 1727
{
    QString utmZone;
1728
    getPose(uas, frame, x, y, z, roll, pitch, yaw, utmZone);
1729 1730 1731
}

void
1732 1733 1734 1735
Pixhawk3DWidget::getPosition(UASInterface* uas,
                             MAV_FRAME frame,
                             double& x, double& y, double& z,
                             QString& utmZone) const
1736
{
1737
    if (!uas)
Lorenz Meier's avatar
Lorenz Meier committed
1738
    {
1739 1740
        return;
    }
1741

1742 1743 1744 1745
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
1746
        double altitude = uas->getAltitudeAMSL();
1747 1748 1749 1750 1751 1752 1753 1754 1755

        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();
1756 1757 1758 1759
    }
}

void
1760 1761 1762
Pixhawk3DWidget::getPosition(UASInterface* uas,
                             MAV_FRAME frame,
                             double& x, double& y, double& z) const
1763 1764
{
    QString utmZone;
1765
    getPosition(uas, frame, x, y, z, utmZone);
1766 1767
}

1768
osg::ref_ptr<osg::Geode>
1769
Pixhawk3DWidget::createLocalGrid(void)
1770 1771
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
1772 1773 1774 1775
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
1776

1777
    float radius = 5.0f;
1778 1779
    float resolution = 0.25f;

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

1783
    // draw a 10m x 10m grid with 0.25m resolution
1784 1785
    for (float i = -radius; i <= radius; i += resolution)
    {
1786
        if (fabs(i / 1.0f - floor(i / 1.0f)) < 0.01f)
1787
        {
1788 1789 1790 1791
            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));
1792 1793 1794
        }
        else
        {
1795 1796 1797 1798 1799
            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));
        }
1800 1801
    }

1802 1803
    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);
1804 1805 1806

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
1807 1808 1809 1810 1811 1812
    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,
1813
                                  0, fineCoords->size()));
1814
    coarseGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0,
1815
                                    coarseCoords->size()));
1816 1817 1818 1819 1820 1821

    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);
1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 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 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895
    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);
1896 1897 1898 1899 1900 1901 1902
    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);
1903 1904
    coarseStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
1905
    coarseGeometry->setStateSet(coarseStateset);
1906

1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940
    // 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);

1941 1942 1943
    return geode;
}

1944
osg::ref_ptr<osg::Geometry>
1945
Pixhawk3DWidget::createTrail(const osg::Vec4& color)
1946
{
1947 1948
    osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry());
    geometry->setUseDisplayList(false);
1949

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

1953 1954
    osg::ref_ptr<osg::DrawArrays> drawArrays(new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP));
    geometry->addPrimitiveSet(drawArrays);
1955

1956 1957 1958 1959
    osg::ref_ptr<osg::Vec4Array> colorArray(new osg::Vec4Array);
    colorArray->push_back(color);
    geometry->setColorArray(colorArray);
    geometry->setColorBinding(osg::Geometry::BIND_OVERALL);
1960 1961 1962 1963 1964 1965

    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);
1966
    geometry->setStateSet(stateset);
1967

1968
    return geometry;
1969 1970
}

1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999
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;
}

2000
osg::ref_ptr<Imagery>
2001
Pixhawk3DWidget::createImagery(void)
2002
{
2003
    return osg::ref_ptr<Imagery>(new Imagery());
2004 2005
}

2006
osg::ref_ptr<osg::Geode>
2007
Pixhawk3DWidget::createPointCloud(void)
2008
{
2009
    int frameSize = 752 * 480;
2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024

    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;
2025 2026
}

2027
osg::ref_ptr<osg::Node>
2028
Pixhawk3DWidget::createTarget(const QColor& color)
2029 2030
{
    osg::ref_ptr<osg::PositionAttitudeTransform> pat =
2031
        new osg::PositionAttitudeTransform;
2032 2033 2034

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

2035
    osg::ref_ptr<osg::Cone> cone = new osg::Cone(osg::Vec3f(0.0f, 0.0f, 0.0f), 0.2f, 0.6f);
2036
    osg::ref_ptr<osg::ShapeDrawable> coneDrawable = new osg::ShapeDrawable(cone);
2037
    coneDrawable->setColor(osg::Vec4f(color.redF(), color.greenF(), color.blueF(), 1.0f));
2038 2039 2040 2041
    coneDrawable->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
    osg::ref_ptr<osg::Geode> coneGeode = new osg::Geode;
    coneGeode->addDrawable(coneDrawable);
    coneGeode->setName("Target");
2042

2043
    pat->addChild(coneGeode);
2044 2045 2046 2047

    return pat;
}

2048 2049 2050 2051
void
Pixhawk3DWidget::setupHUD(void)
{
    osg::ref_ptr<osg::Vec4Array> hudColors(new osg::Vec4Array);
2052 2053
    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));
2054

2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068
    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));
2069

2070
    osg::ref_ptr<osg::Geode> statusGeode = new osg::Geode;
2071 2072 2073 2074 2075 2076 2077
    statusGeode->addDrawable(mHudBackgroundGeometry);
    statusGeode->addDrawable(mStatusText);
    m3DWidget->hudGroup()->addChild(statusGeode);

    mScaleGeode = new HUDScaleGeode;
    mScaleGeode->init(m3DWidget->font());
    m3DWidget->hudGroup()->addChild(mScaleGeode);
2078 2079 2080
}

void
2081
Pixhawk3DWidget::resizeHUD(int width, int height)
2082
{
2083
    int topHUDHeight = 25;
2084 2085
    int bottomHUDHeight = 25;

2086
    osg::Vec3Array* vertices = static_cast<osg::Vec3Array*>(mHudBackgroundGeometry->getVertexArray());
Lorenz Meier's avatar
Lorenz Meier committed
2087 2088
    if (vertices == NULL || vertices->size() != 8)
    {
2089
        osg::ref_ptr<osg::Vec3Array> newVertices = new osg::Vec3Array(8);
2090
        mHudBackgroundGeometry->setVertexArray(newVertices);
2091

2092
        vertices = static_cast<osg::Vec3Array*>(mHudBackgroundGeometry->getVertexArray());
2093 2094
    }

2095 2096 2097 2098
    (*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);
2099
    (*vertices)[4] = osg::Vec3(0, 0, -1);
2100 2101
    (*vertices)[5] = osg::Vec3(width, 0, -1);
    (*vertices)[6] = osg::Vec3(width, bottomHUDHeight, -1);
2102
    (*vertices)[7] = osg::Vec3(0, bottomHUDHeight, -1);
2103

2104
    mStatusText->setPosition(osg::Vec3(10, height - 15, -1.5));
2105

2106 2107
    QMutableMapIterator<int, SystemContainer> it(mSystemContainerMap);
    while (it.hasNext())
Lorenz Meier's avatar
Lorenz Meier committed
2108
    {
2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126
        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);
        }
2127 2128 2129 2130
    }
}

void
2131
Pixhawk3DWidget::updateHUD(UASInterface* uas, MAV_FRAME frame)
2132
{
LM's avatar
LM committed
2133
    if (!uas) return;
2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146
    // 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);
2147 2148 2149 2150

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

Lorenz Meier's avatar
Lorenz Meier committed
2153 2154
    if (frame == MAV_FRAME_GLOBAL)
    {
2155
        double latitude, longitude;
2156
        Imagery::UTMtoLL(x, y, utmZone, latitude, longitude);
2157 2158

        double cursorLatitude, cursorLongitude;
2159
        Imagery::UTMtoLL(cursorPosition.x(), cursorPosition.y(),
2160 2161 2162 2163
                         utmZone, cursorLatitude, cursorLongitude);

        oss.precision(6);
        oss << " Lat = " << latitude <<
2164
            " Lon = " << longitude;
2165 2166

        oss.precision(2);
2167 2168 2169 2170
        oss << " Altitude = " << -z <<
            " r = " << roll <<
            " p = " << pitch <<
            " y = " << yaw;
2171 2172 2173

        oss.precision(6);
        oss << " Cursor [" << cursorLatitude <<
2174
            " " << cursorLongitude << "]";
Lorenz Meier's avatar
Lorenz Meier committed
2175 2176 2177
    }
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
2178 2179 2180 2181 2182 2183 2184 2185
        oss << " x = " << x <<
            " y = " << y <<
            " z = " << z <<
            " r = " << roll <<
            " p = " << pitch <<
            " y = " << yaw <<
            " Cursor [" << cursorPosition.x() <<
            " " << cursorPosition.y() << "]";
2186 2187
    }

2188
    mStatusText->setText(oss.str());
2189

2190
    bool darkBackground = true;
2191 2192
    if (frame == MAV_FRAME_GLOBAL &&
        mImageryNode->getImageryType() == Imagery::GOOGLE_MAP)
Lorenz Meier's avatar
Lorenz Meier committed
2193
    {
2194 2195 2196
        darkBackground = false;
    }

2197 2198 2199
    mScaleGeode->update(height(), m3DWidget->cameraParams().fov(),
                        m3DWidget->cameraManipulator()->getDistance(),
                        darkBackground);
2200 2201 2202
}

void
2203 2204
Pixhawk3DWidget::updateTrails(double robotX, double robotY, double robotZ,
                              osg::ref_ptr<osg::Geode>& trailNode,
2205
                              osg::ref_ptr<osg::Group>& orientationNode,
2206 2207
                              QMap<int, QVector<osg::Vec3d> >& trailMap,
                              QMap<int, int>& trailIndexMap)
2208
{
2209
    QMapIterator<int,int> it(trailIndexMap);
2210

2211
    while (it.hasNext())
Lorenz Meier's avatar
Lorenz Meier committed
2212
    {
2213
        it.next();
2214

2215 2216
        // update trail
        osg::Geometry* geometry = trailNode->getDrawable(it.value() * 2)->asGeometry();
2217 2218 2219 2220
        osg::DrawArrays* drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));

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

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

2223
        vertices->reserve(trail.size());
2224
        for (int i = 0; i < trail.size(); ++i)
Lorenz Meier's avatar
Lorenz Meier committed
2225
        {
2226 2227 2228
            vertices->push_back(osg::Vec3d(trail[i].y() - robotY,
                                           trail[i].x() - robotX,
                                           -(trail[i].z() - robotZ)));
2229 2230
        }

2231 2232 2233 2234
        geometry->setVertexArray(vertices);
        drawArrays->setFirst(0);
        drawArrays->setCount(vertices->size());
        geometry->dirtyBound();
2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260 2261 2262 2263 2264 2265 2266

        // 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();
2267 2268 2269 2270 2271 2272 2273 2274 2275

        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)));
        }
2276 2277 2278
    }
}

2279
void
2280 2281
Pixhawk3DWidget::updateImagery(double originX, double originY,
                               const QString& zone, MAV_FRAME frame)
2282
{
2283
    if (mImageryNode->getImageryType() == Imagery::BLANK_MAP)
Lorenz Meier's avatar
Lorenz Meier committed
2284
    {
2285 2286 2287
        return;
    }

2288
    double viewingRadius = m3DWidget->cameraManipulator()->getDistance() * 10.0;
2289
    if (viewingRadius < 200.0)
Lorenz Meier's avatar
Lorenz Meier committed
2290
    {
2291
        viewingRadius = 200.0;
2292 2293 2294
    }

    double minResolution = 0.25;
2295
    double centerResolution = m3DWidget->cameraManipulator()->getDistance() / 50.0;
2296 2297
    double maxResolution = 1048576.0;

2298
    Imagery::Type imageryType = mImageryNode->getImageryType();
Lorenz Meier's avatar
Lorenz Meier committed
2299 2300
    switch (imageryType)
    {
2301 2302 2303 2304 2305 2306
    case Imagery::GOOGLE_MAP:
        minResolution = 0.25;
        break;
    case Imagery::GOOGLE_SATELLITE:
        minResolution = 0.5;
        break;
2307
    case Imagery::OFFLINE_SATELLITE:
2308 2309
        minResolution = 0.5;
        maxResolution = 0.5;
2310
        break;
2311
    default:
2312
        {}
2313 2314 2315
    }

    double resolution = minResolution;
Lorenz Meier's avatar
Lorenz Meier committed
2316 2317
    while (resolution * 2.0 < centerResolution)
    {
2318 2319
        resolution *= 2.0;
    }
Lorenz Meier's avatar
Lorenz Meier committed
2320 2321 2322

    if (resolution > maxResolution)
    {
2323 2324 2325
        resolution = maxResolution;
    }

2326 2327 2328 2329 2330 2331 2332 2333 2334 2335 2336 2337
    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;
    }

2338 2339
    mImageryNode->draw3D(viewingRadius,
                         resolution,
2340 2341 2342 2343
                         x + xOffset,
                         y + yOffset,
                         -xOffset,
                         -yOffset,
2344
                         zone);
2345 2346

    // prefetch map tiles
Lorenz Meier's avatar
Lorenz Meier committed
2347 2348
    if (resolution / 2.0 >= minResolution)
    {
2349 2350
        mImageryNode->prefetch3D(viewingRadius / 2.0,
                                 resolution / 2.0,
2351 2352
                                 x + xOffset,
                                 y + yOffset,
2353
                                 zone);
2354
    }
Lorenz Meier's avatar
Lorenz Meier committed
2355 2356
    if (resolution * 2.0 <= maxResolution)
    {
2357 2358
        mImageryNode->prefetch3D(viewingRadius * 2.0,
                                 resolution * 2.0,
2359 2360
                                 x + xOffset,
                                 y + yOffset,
2361
                                 zone);
2362 2363
    }

2364
    mImageryNode->update();
2365
}
2366

2367
void
2368 2369 2370 2371
Pixhawk3DWidget::updateTarget(UASInterface* uas, MAV_FRAME frame,
                              double robotX, double robotY, double robotZ,
                              QVector4D& target,
                              osg::ref_ptr<osg::Node>& targetNode)
2372
{
2373 2374 2375
    Q_UNUSED(uas);
    Q_UNUSED(frame);

2376
    osg::PositionAttitudeTransform* pat =
2377 2378
        dynamic_cast<osg::PositionAttitudeTransform*>(targetNode.get());

2379 2380 2381 2382
    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),
2383 2384
                               M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f),
                               0.0, osg::Vec3d(0.0f, 0.0f, 1.0f)));
2385 2386
}

2387
void
2388 2389
Pixhawk3DWidget::updateWaypoints(UASInterface* uas, MAV_FRAME frame,
                                 osg::ref_ptr<WaypointGroupNode>& waypointGroupNode)
2390
{
2391
    waypointGroupNode->update(uas, frame);
2392
}
2393

2394 2395
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)

2396
void
2397 2398 2399
Pixhawk3DWidget::updateObstacles(UASInterface* uas, MAV_FRAME frame,
                                 double robotX, double robotY, double robotZ,
                                 osg::ref_ptr<ObstacleGroupNode>& obstacleGroupNode)
2400
{
2401 2402 2403 2404 2405 2406 2407 2408 2409 2410
    if (frame == MAV_FRAME_GLOBAL)
    {
        obstacleGroupNode->clear();
        return;
    }

    qreal receivedTimestamp;
    px::ObstacleList obstacleList = uas->getObstacleList(receivedTimestamp);

    if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout)
2411
    {
2412
        obstacleGroupNode->update(robotX, robotY, robotZ, obstacleList);
2413 2414 2415 2416 2417
    }
    else
    {
        obstacleGroupNode->clear();
    }
2418 2419
}

2420
void
2421 2422 2423
Pixhawk3DWidget::updatePlannedPath(UASInterface* uas, MAV_FRAME frame,
                                   double robotX, double robotY, double robotZ,
                                   osg::ref_ptr<osg::Geode>& plannedPathNode)
2424
{
2425 2426
    Q_UNUSED(frame);

2427 2428
    qreal receivedTimestamp;
    px::Path path = uas->getPath(receivedTimestamp);
2429

2430
    osg::Geometry* geometry = plannedPathNode->getDrawable(0)->asGeometry();
2431
    osg::DrawArrays* drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));
2432 2433 2434 2435 2436 2437 2438 2439 2440 2441 2442
    osg::Vec4Array* colorArray = reinterpret_cast<osg::Vec4Array*>(geometry->getColorArray());

    geometry->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
    osg::ref_ptr<osg::LineWidth> linewidth(new osg::LineWidth());
    linewidth->setWidth(2.0f);
    geometry->getStateSet()->setAttributeAndModes(linewidth, osg::StateAttribute::ON);

    colorArray->clear();

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

2443
    if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout)
2444
    {
2445 2446 2447 2448 2449 2450
        // find path length
        float length = 0.0f;
        for (int i = 0; i < path.waypoints_size() - 1; ++i)
        {
            const px::Waypoint& wp0 = path.waypoints(i);
            const px::Waypoint& wp1 = path.waypoints(i+1);
2451

2452 2453 2454 2455
            length += qgc::hypot3f(wp0.x() - wp1.x(),
                                   wp0.y() - wp1.y(),
                                   wp0.z() - wp1.z());
        }
2456

2457 2458 2459 2460
        // build path
        if (path.waypoints_size() > 0)
        {
            const px::Waypoint& wp0 = path.waypoints(0);
2461

2462 2463 2464
            vertices->push_back(osg::Vec3d(wp0.y() - robotY,
                                           wp0.x() - robotX,
                                           -(wp0.z() - robotZ)));
2465

2466 2467 2468 2469
            float r, g, b;
            qgc::colormap("autumn", 0, r, g, b);
            colorArray->push_back(osg::Vec4d(r, g, b, 1.0f));
        }
2470

2471 2472 2473 2474 2475
        float lengthCurrent = 0.0f;
        for (int i = 0; i < path.waypoints_size() - 1; ++i)
        {
            const px::Waypoint& wp0 = path.waypoints(i);
            const px::Waypoint& wp1 = path.waypoints(i+1);
2476

2477 2478 2479
            lengthCurrent += qgc::hypot3f(wp0.x() - wp1.x(),
                                          wp0.y() - wp1.y(),
                                          wp0.z() - wp1.z());
2480

2481 2482 2483
            vertices->push_back(osg::Vec3d(wp1.y() - robotY,
                                           wp1.x() - robotX,
                                           -(wp1.z() - robotZ)));
2484

2485
            int colorIdx = lengthCurrent / length * 127.0f;
2486

2487 2488 2489 2490
            float r, g, b;
            qgc::colormap("autumn", colorIdx, r, g, b);
            colorArray->push_back(osg::Vec4f(r, g, b, 1.0f));
        }
2491 2492
    }

2493
    geometry->setVertexArray(vertices);
2494 2495 2496 2497 2498
    drawArrays->setFirst(0);
    drawArrays->setCount(vertices->size());
    geometry->dirtyBound();
}

2499 2500 2501 2502 2503
void
Pixhawk3DWidget::updateRGBD(UASInterface* uas, MAV_FRAME frame,
                            osg::ref_ptr<ImageWindowGeode>& rgbImageNode,
                            osg::ref_ptr<ImageWindowGeode>& depthImageNode)
{
2504 2505
    Q_UNUSED(frame);

2506 2507 2508 2509 2510 2511 2512 2513 2514 2515 2516 2517 2518 2519 2520 2521 2522 2523 2524 2525 2526 2527 2528 2529 2530 2531 2532 2533 2534 2535 2536 2537 2538 2539 2540 2541 2542 2543 2544 2545 2546 2547 2548 2549 2550 2551 2552 2553 2554
    qreal receivedTimestamp;
    px::RGBDImage rgbdImage = uas->getRGBDImage(receivedTimestamp);

    if (rgbdImage.rows() > 0 && rgbdImage.cols() > 0 &&
        QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout)
    {
        rgbImageNode->image()->setImage(rgbdImage.cols(), rgbdImage.rows(), 1,
                                        GL_LUMINANCE, GL_LUMINANCE, GL_UNSIGNED_BYTE,
                                        reinterpret_cast<unsigned char *>(&(*(rgbdImage.mutable_imagedata1()))[0]),
                                        osg::Image::NO_DELETE);
        rgbImageNode->image()->dirty();

        QByteArray coloredDepth(rgbdImage.cols() * rgbdImage.rows() * 3, 0);
        for (uint32_t r = 0; r < rgbdImage.rows(); ++r)
        {
            const float* depth = reinterpret_cast<const float*>(rgbdImage.imagedata2().c_str() + r * rgbdImage.step2());
            uint8_t* pixel = reinterpret_cast<uint8_t*>(coloredDepth.data()) + r * rgbdImage.cols() * 3;
            for (uint32_t c = 0; c < rgbdImage.cols(); ++c)
            {
                if (depth[c] != 0)
                {
                    int idx = fminf(depth[c], 7.0f) / 7.0f * 127.0f;
                    idx = 127 - idx;

                    float r, g, b;
                    qgc::colormap("jet", idx, r, g, b);
                    pixel[0] = r * 255.0f;
                    pixel[1] = g * 255.0f;
                    pixel[2] = b * 255.0f;
                }

                pixel += 3;
            }
        }

        depthImageNode->image()->setImage(rgbdImage.cols(), rgbdImage.rows(), 1,
                                          GL_RGB, GL_RGB, GL_UNSIGNED_BYTE,
                                          reinterpret_cast<unsigned char *>(coloredDepth.data()),
                                          osg::Image::NO_DELETE);
        depthImageNode->image()->dirty();
    }
}

void
Pixhawk3DWidget::updatePointCloud(UASInterface* uas, MAV_FRAME frame,
                                  double robotX, double robotY, double robotZ,
                                  osg::ref_ptr<osg::Geode>& pointCloudNode,
                                  bool colorPointCloudByDistance)
{
2555 2556
    Q_UNUSED(frame);

2557 2558 2559 2560 2561 2562 2563 2564 2565 2566 2567 2568 2569 2570 2571 2572 2573 2574 2575 2576 2577 2578 2579 2580 2581 2582 2583 2584 2585 2586 2587 2588 2589 2590 2591 2592 2593 2594 2595 2596 2597 2598 2599 2600 2601 2602 2603 2604 2605 2606 2607 2608 2609 2610 2611 2612 2613 2614
    qreal receivedTimestamp;
    px::PointCloudXYZRGB pointCloud = uas->getPointCloud(receivedTimestamp);

    osg::Geometry* geometry = pointCloudNode->getDrawable(0)->asGeometry();
    osg::Vec3Array* vertices = static_cast<osg::Vec3Array*>(geometry->getVertexArray());
    osg::Vec4Array* colors = static_cast<osg::Vec4Array*>(geometry->getColorArray());

    if (QGC::groundTimeSeconds() - receivedTimestamp > kMessageTimeout)
    {
        geometry->removePrimitiveSet(0, geometry->getNumPrimitiveSets());
        return;
    }

    for (int i = 0; i < pointCloud.points_size(); ++i)
    {
        const px::PointCloudXYZRGB_PointXYZRGB& p = pointCloud.points(i);

        double x = p.x() - robotX;
        double y = p.y() - robotY;
        double z = p.z() - robotZ;


        (*vertices)[i].set(y, x, -z);

        if (!colorPointCloudByDistance)
        {
            float rgb = p.rgb();

            float b = *(reinterpret_cast<unsigned char*>(&rgb)) / 255.0f;
            float g = *(1 + reinterpret_cast<unsigned char*>(&rgb)) / 255.0f;
            float r = *(2 + reinterpret_cast<unsigned char*>(&rgb)) / 255.0f;

            (*colors)[i].set(r, g, b, 1.0f);
        }
        else
        {
            double dist = sqrt(x * x + y * y + z * z);
            int colorIndex = static_cast<int>(fmin(dist / 7.0 * 127.0, 127.0));

            float r, g, b;
            qgc::colormap("jet", colorIndex, r, g, b);

            (*colors)[i].set(r, g, b, 1.0f);
        }
    }

    if (geometry->getNumPrimitiveSets() == 0)
    {
        geometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POINTS,
                                  0, pointCloud.points_size()));
    }
    else
    {
        osg::DrawArrays* drawarrays = static_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));
        drawarrays->setCount(pointCloud.points_size());
    }
}

2615
#endif
2616

2617
int
2618
Pixhawk3DWidget::findWaypoint(const QPoint& mousePos)
2619
{
2620
    if (!m3DWidget->getSceneData() || !mActiveUAS)
2621
    {
2622 2623
        return -1;
    }
2624

2625 2626 2627 2628 2629 2630 2631 2632 2633 2634 2635 2636 2637
    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++)
2638
        {
2639
            for (uint i = 0 ; i < it->nodePath.size(); ++i)
2640
            {
2641 2642 2643
                osg::Node* node = it->nodePath[i];
                std::string nodeName = node->getName();
                if (nodeName.substr(0, 2).compare("wp") == 0)
2644
                {
2645
                    if (node->getParent(0)->getParent(0) == waypointGroupNode.get())
2646
                    {
2647
                        return atoi(nodeName.substr(2).c_str());
2648 2649 2650 2651 2652 2653 2654 2655 2656
                    }
                }
            }
        }
    }

    return -1;
}

2657

2658 2659 2660
bool
Pixhawk3DWidget::findTarget(int mouseX, int mouseY)
{
2661
    if (m3DWidget->getSceneData())
2662
    {
2663 2664
        osgUtil::LineSegmentIntersector::Intersections intersections;

2665
        if (m3DWidget->computeIntersections(mouseX, height() - mouseY, intersections))
2666
        {
2667
            for (osgUtil::LineSegmentIntersector::Intersections::iterator
2668 2669 2670 2671
                    it = intersections.begin(); it != intersections.end(); it++)
            {
                for (uint i = 0 ; i < it->nodePath.size(); ++i)
                {
2672
                    std::string nodeName = it->nodePath[i]->getName();
2673 2674
                    if (nodeName.compare("Target") == 0)
                    {
2675 2676 2677 2678 2679 2680 2681 2682 2683 2684
                        return true;
                    }
                }
            }
        }
    }

    return false;
}

2685 2686 2687 2688 2689 2690 2691 2692 2693 2694 2695 2696 2697 2698 2699 2700 2701 2702 2703 2704 2705 2706 2707 2708 2709 2710 2711 2712 2713 2714 2715 2716 2717 2718 2719
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;
}

2720 2721 2722 2723 2724 2725
void
Pixhawk3DWidget::showInsertWaypointMenu(const QPoint &cursorPos)
{
    QMenu menu;
    menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
2726
    menu.addAction("Select target", this, SLOT(selectTarget()));
2727 2728 2729 2730 2731 2732 2733 2734 2735
    menu.exec(cursorPos);
}

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

    QString text;
2736
    text = QString("Move waypoint %1").arg(QString::number(mSelectedWpIndex));
2737 2738
    menu.addAction(text, this, SLOT(moveWaypointPosition()));

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

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

2745
    text = QString("Delete waypoint %1").arg(QString::number(mSelectedWpIndex));
2746 2747 2748 2749 2750
    menu.addAction(text, this, SLOT(deleteWaypoint()));

    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
    menu.exec(cursorPos);
}
2751 2752 2753 2754 2755 2756 2757 2758

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