Pixhawk3DWidget.cc 64 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 41
#include <osg/LineWidth>
#include <osg/ShapeDrawable>

42
#include "../MainWindow.h"
43 44
#include "PixhawkCheetahGeode.h"
#include "UASManager.h"
45

46
#include "QGC.h"
47
#include "gpl.h"
48

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

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

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

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

76
    // generate map model
77 78
    mImageryNode = createImagery();
    m3DWidget->worldMap()->addChild(mImageryNode, false);
79

80
    setupHUD();
81

82
    buildLayout();
83

84 85 86 87 88 89
    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)));
90

91 92
    MainWindow* parentWindow = qobject_cast<MainWindow*>(parent);
    parentWindow->addDockWidget(Qt::LeftDockWidgetArea, mViewParamWidget);
93

94
    mViewParamWidget->hide();
95

96 97 98
    setFocusPolicy(Qt::StrongFocus);
    setMouseTracking(true);
}
99

100 101
Pixhawk3DWidget::~Pixhawk3DWidget()
{
102

103 104
}

105 106
void
Pixhawk3DWidget::activeSystemChanged(UASInterface* uas)
107
{
108 109 110
    mActiveSystemId = uas->getUASID();

    mActiveUAS = uas;
111

112
    mMode = DEFAULT_MODE;
113 114
}

115
void
116
Pixhawk3DWidget::systemCreated(UASInterface *uas)
117
{
118 119 120
    int systemId = uas->getUASID();

    if (mSystemContainerMap.contains(systemId))
121 122 123 124
    {
        return;
    }

125 126
    mSystemViewParamMap.insert(systemId, SystemViewParamsPtr(new SystemViewParams(systemId)));
    mSystemContainerMap.insert(systemId, SystemContainer());
127

128 129 130 131
    connect(uas, SIGNAL(localPositionChanged(UASInterface*,int,double,double,double,quint64)),
            this, SLOT(localPositionChanged(UASInterface*,int,double,double,double,quint64)));
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)),
            this, SLOT(attitudeChanged(UASInterface*,int,double,double,double,quint64)));
132

133
    initializeSystem(systemId, uas->getColor());
134

135
    emit systemCreatedSignal(uas);
136 137
}

138
void
139 140 141
Pixhawk3DWidget::localPositionChanged(UASInterface* uas, int component,
                                      double x, double y, double z,
                                      quint64 time)
142
{
143 144 145
    int systemId = uas->getUASID();

    if (!mSystemContainerMap.contains(systemId))
146 147 148 149
    {
        return;
    }

150 151 152 153 154 155 156
    SystemContainer& systemData = mSystemContainerMap[systemId];

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

    // update trail data
    if (!systemData.trailMap().contains(component))
157
    {
158 159 160 161
        systemData.trailMap().insert(component, QVector<osg::Vec3d>());
        systemData.trailMap()[component].reserve(10000);
        systemData.trailIndexMap().insert(component,
                                          systemData.trailMap().size() - 1);
162 163 164 165 166

        osg::Vec4 color((float)qrand() / RAND_MAX,
                        (float)qrand() / RAND_MAX,
                        (float)qrand() / RAND_MAX,
                        0.5);
167

168
        systemData.trailNode()->addDrawable(createTrail(color));
169
        systemData.trailNode()->addDrawable(createLink(uas->getColor()));
170 171
    }

172
    QVector<osg::Vec3d>& trail = systemData.trailMap()[component];
173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204

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

205
void
206 207 208
Pixhawk3DWidget::attitudeChanged(UASInterface* uas, int component,
                                 double roll, double pitch, double yaw,
                                 quint64 time)
209
{
210
    int systemId = uas->getUASID();
211

212
    if (!mSystemContainerMap.contains(systemId))
213 214 215 216
    {
        return;
    }

217 218 219 220 221
    // 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);
222 223
}

224
void
225
Pixhawk3DWidget::showViewParamWindow(void)
226
{
227 228 229 230 231
    if (mViewParamWidget->isVisible())
    {
        mViewParamWidget->hide();
    }
    else
232
    {
233
        mViewParamWidget->show();
234
    }
235 236
}

237
void
238
Pixhawk3DWidget::followCameraChanged(int systemId)
239
{
240
    if (systemId == -1)
241
    {
242
        mFollowCameraId = -1;
243 244
    }

245 246
    UASInterface* uas = UASManager::instance()->getUASForId(systemId);
    if (!uas)
247
    {
248
        return;
249
    }
250 251

    if (mFollowCameraId != systemId)
252
    {
253 254 255 256 257 258 259 260
        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;
261 262 263 264
    }
}

void
265
Pixhawk3DWidget::recenterActiveCamera(void)
266
{
267
    if (mFollowCameraId != -1)
268
    {
269 270
        UASInterface* uas = UASManager::instance()->getUASForId(mFollowCameraId);
        if (!uas)
271
        {
272
            return;
273 274
        }

275 276
        double x = 0.0, y = 0.0, z = 0.0;
        getPosition(uas, mGlobalViewParams->frame(), x, y, z);
277

278 279 280
        mCameraPos = QVector3D(x, y, z);

        m3DWidget->recenterCamera(y, x, -z);
281 282 283
    }
}

284
void
285
Pixhawk3DWidget::modelChanged(int systemId, int index)
286
{
287
    if (!mSystemContainerMap.contains(systemId))
288
    {
289
        return;
290
    }
291

292 293 294 295 296 297
    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());
298 299
}

300
void
301
Pixhawk3DWidget::setBirdEyeView(void)
302
{
303
    mViewParamWidget->setFollowCameraId(-1);
304

305
    m3DWidget->rotateCamera(0.0, 0.0, 0.0);
306
    m3DWidget->setCameraDistance(100.0);
307
}
308

309
void
310
Pixhawk3DWidget::selectTargetHeading(void)
311
{
312
    if (!mActiveUAS)
313 314 315
    {
        return;
    }
316

317 318
    osg::Vec2d p;

319
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
320
    {
321
        double altitude = mActiveUAS->getAltitude();
322

323 324
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), altitude);
325

326
        p.set(cursorWorldCoords.x(), cursorWorldCoords.y());
327
    }
328
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
329
    {
330
        double z = mActiveUAS->getLocalZ();
331

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

335
        p.set(cursorWorldCoords.x(), cursorWorldCoords.y());
336
    }
337

338 339 340
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

341
    target.setW(atan2(p.y() - target.y(), p.x() - target.x()));
342 343 344 345 346
}

void
Pixhawk3DWidget::selectTarget(void)
{
347
    if (!mActiveUAS)
348 349 350
    {
        return;
    }
351
    if (!mActiveUAS->getParamManager())
352 353 354
    {
        return;
    }
355

356 357 358 359
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
360
    {
361
        double altitude = mActiveUAS->getAltitude();
362

363 364
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, altitude);
365

366
        QVariant zTarget;
367
        if (!mActiveUAS->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
368 369 370 371
        {
            zTarget = -altitude;
        }

372
        target = QVector4D(cursorWorldCoords.x(), cursorWorldCoords.y(),
373
                           zTarget.toReal(), 0.0);
374
    }
375
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
376
    {
377
        double z = mActiveUAS->getLocalZ();
378

379 380
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, -z);
381

382
        QVariant zTarget;
383
        if (!mActiveUAS->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
384 385 386 387
        {
            zTarget = z;
        }

388
        target = QVector4D(cursorWorldCoords.x(), cursorWorldCoords.y(),
389
                           zTarget.toReal(), 0.0);
390
    }
391

392
    int systemId = mActiveUAS->getUASID();
393

394 395 396 397 398 399 400
    QMap<int, SystemViewParamsPtr>::iterator it = mSystemViewParamMap.find(systemId);
    if (it != mSystemViewParamMap.end())
    {
        it.value()->displayTarget() = true;
    }

    mMode = SELECT_TARGET_HEADING_MODE;
401 402 403 404 405 406 407
}

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

408 409 410 411 412
    SystemContainer& systemData = mSystemContainerMap[mActiveUAS->getUASID()];
    QVector4D& target = systemData.target();

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

415 416 417
void
Pixhawk3DWidget::insertWaypoint(void)
{
418
    if (!mActiveUAS)
419 420 421
    {
        return;
    }
422

423
    Waypoint* wp = NULL;
424
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
425
    {
426 427 428
        double latitude = mActiveUAS->getLatitude();
        double longitude = mActiveUAS->getLongitude();
        double altitude = mActiveUAS->getAltitude();
429 430 431 432
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

433 434
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, altitude);
435

436
        Imagery::UTMtoLL(cursorWorldCoords.x(), cursorWorldCoords.y(), utmZone,
437 438
                         latitude, longitude);

439
        wp = new Waypoint(0, longitude, latitude, altitude, 0.0, 0.25);
440
    }
441
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
442
    {
443
        double z = mActiveUAS->getLocalZ();
444

445 446
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(mCachedMousePos, -z);
447

448 449
        wp = new Waypoint(0, cursorWorldCoords.x(),
                          cursorWorldCoords.y(), z, 0.0, 0.25);
450 451 452 453
    }

    if (wp)
    {
454 455
        wp->setFrame(mGlobalViewParams->frame());
        mActiveUAS->getWaypointManager()->addWaypointEditable(wp);
456 457
    }

458 459
    mSelectedWpIndex = wp->getId();
    mMode = MOVE_WAYPOINT_HEADING_MODE;
460 461 462
}

void
463
Pixhawk3DWidget::moveWaypointPosition(void)
464
{
465
    if (mMode != MOVE_WAYPOINT_POSITION_MODE)
466
    {
467
        mMode = MOVE_WAYPOINT_POSITION_MODE;
468 469 470
        return;
    }

471
    if (!mActiveUAS)
472 473 474 475 476
    {
        return;
    }

    const QVector<Waypoint *> waypoints =
477 478
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
479

480
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
481
    {
482 483 484
        double latitude = mActiveUAS->getLatitude();
        double longitude = mActiveUAS->getLongitude();
        double altitude = mActiveUAS->getAltitude();
485 486 487 488
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

489 490
        QPointF cursorWorldCoords =
            m3DWidget->worldCursorPosition(m3DWidget->mouseCursorCoords(), altitude);
491

492
        Imagery::UTMtoLL(cursorWorldCoords.x(), cursorWorldCoords.y(),
493
                         utmZone, latitude, longitude);
494 495 496 497

        waypoint->setX(longitude);
        waypoint->setY(latitude);
    }
498
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
499
    {
500
        double z = mActiveUAS->getLocalZ();
501

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

505 506
        waypoint->setX(cursorWorldCoords.x());
        waypoint->setY(cursorWorldCoords.y());
507 508 509
    }
}

510 511 512
void
Pixhawk3DWidget::moveWaypointHeading(void)
{
513
    if (mMode != MOVE_WAYPOINT_HEADING_MODE)
514
    {
515
        mMode = MOVE_WAYPOINT_HEADING_MODE;
516 517 518
        return;
    }

519
    if (!mActiveUAS)
520 521 522 523 524
    {
        return;
    }

    const QVector<Waypoint *> waypoints =
525 526
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
527 528 529

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

530
    if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
531 532 533 534 535 536 537
    {
        double latitude = waypoint->getY();
        double longitude = waypoint->getX();
        z = -waypoint->getZ();
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
    }
538
    else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
539
    {
540
        z = mActiveUAS->getLocalZ();
541 542
    }

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

546 547
    double yaw = atan2(cursorWorldCoords.y() - waypoint->getY(),
                       cursorWorldCoords.x() - waypoint->getX());
548 549 550 551 552
    yaw = osg::RadiansToDegrees(yaw);

    waypoint->setYaw(yaw);
}

553 554 555
void
Pixhawk3DWidget::deleteWaypoint(void)
{
556
    if (mActiveUAS)
557
    {
558
        mActiveUAS->getWaypointManager()->removeWaypoint(mSelectedWpIndex);
559 560 561 562 563 564
    }
}

void
Pixhawk3DWidget::setWaypointAltitude(void)
{
565
    if (!mActiveUAS)
566 567 568
    {
        return;
    }
569

570 571
    bool ok;
    const QVector<Waypoint *> waypoints =
572 573
        mActiveUAS->getWaypointManager()->getWaypointEditableList();
    Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
574

575
    double altitude = waypoint->getZ();
576
    if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
577 578 579 580 581
    {
        altitude = -altitude;
    }

    double newAltitude =
582
        QInputDialog::getDouble(this, tr("Set altitude of waypoint %1").arg(mSelectedWpIndex),
583 584 585
                                tr("Altitude (m):"), waypoint->getZ(), -1000.0, 1000.0, 1, &ok);
    if (ok)
    {
586
        if (mGlobalViewParams->frame() == MAV_FRAME_GLOBAL)
587 588 589
        {
            waypoint->setZ(newAltitude);
        }
590
        else if (mGlobalViewParams->frame() == MAV_FRAME_LOCAL_NED)
591 592
        {
            waypoint->setZ(-newAltitude);
593
        }
594 595 596 597 598 599
    }
}

void
Pixhawk3DWidget::clearAllWaypoints(void)
{
600
    if (mActiveUAS)
601
    {
602
        const QVector<Waypoint *> waypoints =
603
            mActiveUAS->getWaypointManager()->getWaypointEditableList();
604 605
        for (int i = waypoints.size() - 1; i >= 0; --i)
        {
606
            mActiveUAS->getWaypointManager()->removeWaypoint(i);
607
        }
608 609 610
    }
}

611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698
void
Pixhawk3DWidget::sizeChanged(int width, int height)
{
    resizeHUD(width, height);
}

void
Pixhawk3DWidget::update(void)
{
    MAV_FRAME frame = mGlobalViewParams->frame();

    // set node visibility
    m3DWidget->worldMap()->setChildValue(mWorldGridNode,
                                        mGlobalViewParams->displayWorldGrid());
    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();

        osg::ref_ptr<osg::Switch>& rollingMap = systemNode->rollingMap();
        rollingMap->setChildValue(systemData.localGridNode(),
                                  systemViewParams->displayLocalGrid());
        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());
        rollingMap->setChildValue(systemData.plannedPathNode(),
                                  systemViewParams->displayPlannedPath());

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

    mImageryNode->setImageryType(mGlobalViewParams->imageryType());

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

699
            setBirdEyeView();
700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780
            mInitCameraPos = true;
        }
    }

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

        int systemId = it.key();

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

        osg::ref_ptr<SystemGroupNode>& systemNode = m3DWidget->systemGroup(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);

        if (systemViewParams->displayTarget())
        {
            if (systemData.target().isNull())
            {
                systemViewParams->displayTarget() = false;
            }
            else
            {
                updateTarget(uas, frame, x, y, z, systemData.target(),
                             systemData.targetNode());
            }
        }
        if (systemViewParams->displayTrails())
        {
            updateTrails(x, y, z, systemData.trailNode(),
                         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());
        }
#endif
    }

    if (frame == MAV_FRAME_GLOBAL &&
        mGlobalViewParams->imageryType() != Imagery::BLANK_MAP)
    {
//        updateImagery(robotX, robotY, robotZ, utmZone);
    }

781 782 783 784
    if (mActiveUAS)
    {
      updateHUD(mActiveUAS, frame);
    }
785 786 787 788 789 790 791

    layout()->update();
}

void
Pixhawk3DWidget::addModels(QVector< osg::ref_ptr<osg::Node> >& models,
                           const QColor& systemColor)
792 793
{
    QDir directory("models");
lm's avatar
lm committed
794
    QStringList files = directory.entryList(QStringList("*.osg"), QDir::Files);
795 796

    // add Pixhawk Bravo model
797
    models.push_back(PixhawkCheetahGeode::create(systemColor));
798

hengli's avatar
hengli committed
799 800 801
    // 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);
802
    sphereDrawable->setColor(osg::Vec4f(systemColor.redF(), systemColor.greenF(), systemColor.blueF(), 1.0f));
hengli's avatar
hengli committed
803 804 805
    osg::ref_ptr<osg::Geode> sphereGeode = new osg::Geode;
    sphereGeode->addDrawable(sphereDrawable);
    sphereGeode->setName("Sphere (0.1m)");
806
    models.push_back(sphereGeode);
hengli's avatar
hengli committed
807

808
    // add all other models in folder
809 810
    for (int i = 0; i < files.size(); ++i)
    {
811
        osg::ref_ptr<osg::Node> node =
812
            osgDB::readNodeFile(directory.absoluteFilePath(files[i]).toStdString().c_str());
813

814 815
        if (node)
        {
816
            models.push_back(node);
817 818 819
        }
        else
        {
820
            printf("%s\n", QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
lm's avatar
lm committed
821
        }
822 823 824 825 826 827
    }
}

void
Pixhawk3DWidget::buildLayout(void)
{
828
    QPushButton* viewParamWindowButton = new QPushButton(this);
829
    viewParamWindowButton->setCheckable(true);
830
    viewParamWindowButton->setText("View Parameters");
831

832 833 834
    QHBoxLayout* layoutTop = new QHBoxLayout;
    layoutTop->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding));
    layoutTop->addWidget(viewParamWindowButton);
835 836 837 838

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

839 840
    QPushButton* birdEyeViewButton = new QPushButton(this);
    birdEyeViewButton->setText("Bird's Eye View");
841 842 843

    QHBoxLayout* layoutBottom = new QHBoxLayout;
    layoutBottom->addWidget(recenterButton);
844
    layoutBottom->addWidget(birdEyeViewButton);
845
    layoutBottom->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding));
846 847 848 849

    QGridLayout* layout = new QGridLayout(this);
    layout->setMargin(0);
    layout->setSpacing(2);
850 851 852
    layout->addLayout(layoutTop, 0, 0);
    layout->addWidget(m3DWidget, 1, 0);
    layout->addLayout(layoutBottom, 2, 0);
853 854 855
    layout->setRowStretch(0, 1);
    layout->setRowStretch(1, 100);
    layout->setRowStretch(2, 1);
856

857 858 859 860
    connect(viewParamWindowButton, SIGNAL(clicked()),
            this, SLOT(showViewParamWindow()));
    connect(recenterButton, SIGNAL(clicked()),
            this, SLOT(recenterActiveCamera()));
861 862
    connect(birdEyeViewButton, SIGNAL(clicked()),
            this, SLOT(setBirdEyeView()));
863 864
}

865
void
866
Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
867
{
868 869
    QWidget::keyPressEvent(event);
    if (event->isAccepted())
870
    {
871 872 873
        return;
    }

874
    m3DWidget->handleKeyPressEvent(event);
875 876
}

877
void
878
Pixhawk3DWidget::keyReleaseEvent(QKeyEvent* event)
879
{
880 881
    QWidget::keyReleaseEvent(event);
    if (event->isAccepted())
882
    {
883
        return;
884 885
    }

886
    m3DWidget->handleKeyReleaseEvent(event);
887 888
}

889 890 891
void
Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
{
892 893 894 895 896 897
    QWidget::mousePressEvent(event);
    if (event->isAccepted())
    {
        return;
    }

898 899
    if (event->button() == Qt::LeftButton)
    {
900
        if (mMode == SELECT_TARGET_HEADING_MODE)
901
        {
902
            setTarget();
903
            event->accept();
904 905
        }

906
        if (mMode != DEFAULT_MODE)
907
        {
908 909
            mMode = DEFAULT_MODE;
            event->accept();
910 911
        }

912 913
        if (event->modifiers() == Qt::ShiftModifier)
        {
914 915
            mSelectedWpIndex = findWaypoint(event->pos());
            if (mSelectedWpIndex == -1)
916
            {
917
                mCachedMousePos = event->pos();
918

919
                showInsertWaypointMenu(event->globalPos());
920 921 922
            }
            else
            {
923 924
                showEditWaypointMenu(event->globalPos());
            }
925
            event->accept();
926 927 928

            return;
        }
929 930
    }

931
    m3DWidget->handleMousePressEvent(event);
932 933
}

934
void
935
Pixhawk3DWidget::mouseReleaseEvent(QMouseEvent* event)
936
{
937 938 939 940 941
    QWidget::mouseReleaseEvent(event);
    if (event->isAccepted())
    {
        return;
    }
942

943
    m3DWidget->handleMouseReleaseEvent(event);
944 945
}

946 947 948
void
Pixhawk3DWidget::mouseMoveEvent(QMouseEvent* event)
{
949 950 951 952 953 954 955
    QWidget::mouseMoveEvent(event);
    if (event->isAccepted())
    {
        return;
    }

    if (mMode == SELECT_TARGET_HEADING_MODE)
956 957
    {
        selectTargetHeading();
958
        event->accept();
959
    }
960
    if (mMode == MOVE_WAYPOINT_POSITION_MODE)
961 962
    {
        moveWaypointPosition();
963
        event->accept();
964
    }
965
    if (mMode == MOVE_WAYPOINT_HEADING_MODE)
966 967
    {
        moveWaypointHeading();
968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 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
        event->accept();
    }

    m3DWidget->handleMouseMoveEvent(event);
}

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

    m3DWidget->handleWheelEvent(event);
}

void
Pixhawk3DWidget::showEvent(QShowEvent* event)
{
    emit visibilityChanged(true);
}

void
Pixhawk3DWidget::hideEvent(QHideEvent* event)
{
    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);

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

    // 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());
1053
    }
1054

1055 1056 1057 1058 1059
    systemData.modelNode() = systemData.models().front();
    systemNode->egocentricMap()->addChild(systemData.modelNode());

    connect(systemViewParams.data(), SIGNAL(modelChangedSignal(int,int)),
            this, SLOT(modelChanged(int,int)));
1060 1061
}

1062
void
1063 1064 1065
Pixhawk3DWidget::getPose(UASInterface* uas,
                         MAV_FRAME frame,
                         double& x, double& y, double& z,
1066
                         double& roll, double& pitch, double& yaw,
1067
                         QString& utmZone) const
1068
{
1069 1070 1071 1072
    if (!uas)
    {
        return;
    }
1073

1074 1075 1076 1077 1078 1079 1080 1081
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
        double altitude = uas->getAltitude();

        Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
        z = -altitude;
1082
    }
1083 1084 1085 1086 1087
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
        x = uas->getLocalX();
        y = uas->getLocalY();
        z = uas->getLocalZ();
1088
    }
1089 1090 1091 1092

    roll = uas->getRoll();
    pitch = uas->getPitch();
    yaw = uas->getYaw();
1093 1094 1095
}

void
1096 1097 1098 1099
Pixhawk3DWidget::getPose(UASInterface* uas,
                         MAV_FRAME frame,
                         double& x, double& y, double& z,
                         double& roll, double& pitch, double& yaw) const
1100 1101
{
    QString utmZone;
1102
    getPose(uas, frame, x, y, z, roll, pitch, yaw, utmZone);
1103 1104 1105
}

void
1106 1107 1108 1109
Pixhawk3DWidget::getPosition(UASInterface* uas,
                             MAV_FRAME frame,
                             double& x, double& y, double& z,
                             QString& utmZone) const
1110
{
1111
    if (!uas)
Lorenz Meier's avatar
Lorenz Meier committed
1112
    {
1113 1114
        return;
    }
1115

1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
        double altitude = uas->getAltitude();

        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();
1130 1131 1132 1133
    }
}

void
1134 1135 1136
Pixhawk3DWidget::getPosition(UASInterface* uas,
                             MAV_FRAME frame,
                             double& x, double& y, double& z) const
1137 1138
{
    QString utmZone;
1139
    getPosition(uas, frame, x, y, z, utmZone);
1140 1141
}

1142
osg::ref_ptr<osg::Geode>
1143
Pixhawk3DWidget::createLocalGrid(void)
1144 1145
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
1146 1147 1148 1149
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
1150

1151
    float radius = 5.0f;
1152 1153
    float resolution = 0.25f;

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

1157
    // draw a 10m x 10m grid with 0.25m resolution
1158 1159
    for (float i = -radius; i <= radius; i += resolution)
    {
1160
        if (fabs(i / 1.0f - floor(i / 1.0f)) < 0.01f)
1161
        {
1162 1163 1164 1165
            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));
1166 1167 1168
        }
        else
        {
1169 1170 1171 1172 1173
            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));
        }
1174 1175
    }

1176 1177
    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);
1178 1179 1180

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
1181 1182 1183 1184 1185 1186
    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,
1187
                                  0, fineCoords->size()));
1188
    coarseGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0,
1189
                                    coarseCoords->size()));
1190 1191 1192 1193 1194 1195

    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);
1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 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
    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);
1270 1271 1272 1273 1274 1275 1276
    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);
1277 1278
    coarseStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
1279
    coarseGeometry->setStateSet(coarseStateset);
1280

1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314
    // 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);

1315 1316 1317
    return geode;
}

1318
osg::ref_ptr<osg::Geometry>
1319
Pixhawk3DWidget::createTrail(const osg::Vec4& color)
1320
{
1321 1322
    osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry());
    geometry->setUseDisplayList(false);
1323

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

1327 1328
    osg::ref_ptr<osg::DrawArrays> drawArrays(new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP));
    geometry->addPrimitiveSet(drawArrays);
1329

1330 1331 1332 1333
    osg::ref_ptr<osg::Vec4Array> colorArray(new osg::Vec4Array);
    colorArray->push_back(color);
    geometry->setColorArray(colorArray);
    geometry->setColorBinding(osg::Geometry::BIND_OVERALL);
1334 1335 1336 1337 1338 1339

    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);
1340
    geometry->setStateSet(stateset);
1341

1342
    return geometry;
1343 1344
}

1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373
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;
}

1374
osg::ref_ptr<Imagery>
1375
Pixhawk3DWidget::createImagery(void)
1376
{
1377
    return osg::ref_ptr<Imagery>(new Imagery());
1378 1379
}

1380
osg::ref_ptr<osg::Geode>
1381
Pixhawk3DWidget::createPointCloud(void)
1382
{
1383
    int frameSize = 752 * 480;
1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398

    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;
1399 1400
}

1401
osg::ref_ptr<osg::Node>
1402
Pixhawk3DWidget::createTarget(const QColor& color)
1403 1404
{
    osg::ref_ptr<osg::PositionAttitudeTransform> pat =
1405
        new osg::PositionAttitudeTransform;
1406 1407 1408

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

1409
    osg::ref_ptr<osg::Cone> cone = new osg::Cone(osg::Vec3f(0.0f, 0.0f, 0.0f), 0.2f, 0.6f);
1410
    osg::ref_ptr<osg::ShapeDrawable> coneDrawable = new osg::ShapeDrawable(cone);
1411
    coneDrawable->setColor(osg::Vec4f(color.redF(), color.greenF(), color.blueF(), 1.0f));
1412 1413 1414 1415
    coneDrawable->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
    osg::ref_ptr<osg::Geode> coneGeode = new osg::Geode;
    coneGeode->addDrawable(coneDrawable);
    coneGeode->setName("Target");
1416

1417
    pat->addChild(coneGeode);
1418 1419 1420 1421

    return pat;
}

1422 1423 1424 1425
void
Pixhawk3DWidget::setupHUD(void)
{
    osg::ref_ptr<osg::Vec4Array> hudColors(new osg::Vec4Array);
1426 1427
    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));
1428

1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442
    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));
1443

1444
    osg::ref_ptr<osg::Geode> statusGeode = new osg::Geode;
1445 1446 1447 1448 1449 1450 1451
    statusGeode->addDrawable(mHudBackgroundGeometry);
    statusGeode->addDrawable(mStatusText);
    m3DWidget->hudGroup()->addChild(statusGeode);

    mScaleGeode = new HUDScaleGeode;
    mScaleGeode->init(m3DWidget->font());
    m3DWidget->hudGroup()->addChild(mScaleGeode);
1452 1453 1454
}

void
1455
Pixhawk3DWidget::resizeHUD(int width, int height)
1456
{
1457
    int topHUDHeight = 25;
1458 1459
    int bottomHUDHeight = 25;

1460
    osg::Vec3Array* vertices = static_cast<osg::Vec3Array*>(mHudBackgroundGeometry->getVertexArray());
Lorenz Meier's avatar
Lorenz Meier committed
1461 1462
    if (vertices == NULL || vertices->size() != 8)
    {
1463
        osg::ref_ptr<osg::Vec3Array> newVertices = new osg::Vec3Array(8);
1464
        mHudBackgroundGeometry->setVertexArray(newVertices);
1465

1466
        vertices = static_cast<osg::Vec3Array*>(mHudBackgroundGeometry->getVertexArray());
1467 1468
    }

1469 1470 1471 1472
    (*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);
1473
    (*vertices)[4] = osg::Vec3(0, 0, -1);
1474 1475
    (*vertices)[5] = osg::Vec3(width, 0, -1);
    (*vertices)[6] = osg::Vec3(width, bottomHUDHeight, -1);
1476
    (*vertices)[7] = osg::Vec3(0, bottomHUDHeight, -1);
1477

1478
    mStatusText->setPosition(osg::Vec3(10, height - 15, -1.5));
1479

1480 1481
    QMutableMapIterator<int, SystemContainer> it(mSystemContainerMap);
    while (it.hasNext())
Lorenz Meier's avatar
Lorenz Meier committed
1482
    {
1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500
        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);
        }
1501 1502 1503 1504
    }
}

void
1505
Pixhawk3DWidget::updateHUD(UASInterface* uas, MAV_FRAME frame)
1506
{
1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519
    // 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);
1520 1521 1522 1523

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

Lorenz Meier's avatar
Lorenz Meier committed
1526 1527
    if (frame == MAV_FRAME_GLOBAL)
    {
1528
        double latitude, longitude;
1529
        Imagery::UTMtoLL(x, y, utmZone, latitude, longitude);
1530 1531

        double cursorLatitude, cursorLongitude;
1532
        Imagery::UTMtoLL(cursorPosition.x(), cursorPosition.y(),
1533 1534 1535 1536
                         utmZone, cursorLatitude, cursorLongitude);

        oss.precision(6);
        oss << " Lat = " << latitude <<
1537
            " Lon = " << longitude;
1538 1539

        oss.precision(2);
1540 1541 1542 1543
        oss << " Altitude = " << -z <<
            " r = " << roll <<
            " p = " << pitch <<
            " y = " << yaw;
1544 1545 1546

        oss.precision(6);
        oss << " Cursor [" << cursorLatitude <<
1547
            " " << cursorLongitude << "]";
Lorenz Meier's avatar
Lorenz Meier committed
1548 1549 1550
    }
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
1551 1552 1553 1554 1555 1556 1557 1558
        oss << " x = " << x <<
            " y = " << y <<
            " z = " << z <<
            " r = " << roll <<
            " p = " << pitch <<
            " y = " << yaw <<
            " Cursor [" << cursorPosition.x() <<
            " " << cursorPosition.y() << "]";
1559 1560
    }

1561
    mStatusText->setText(oss.str());
1562

1563
    bool darkBackground = true;
1564 1565
    if (frame == MAV_FRAME_GLOBAL &&
        mImageryNode->getImageryType() == Imagery::GOOGLE_MAP)
Lorenz Meier's avatar
Lorenz Meier committed
1566
    {
1567 1568 1569
        darkBackground = false;
    }

1570 1571 1572
    mScaleGeode->update(height(), m3DWidget->cameraParams().fov(),
                        m3DWidget->cameraManipulator()->getDistance(),
                        darkBackground);
1573 1574 1575
}

void
1576 1577 1578 1579
Pixhawk3DWidget::updateTrails(double robotX, double robotY, double robotZ,
                              osg::ref_ptr<osg::Geode>& trailNode,
                              QMap<int, QVector<osg::Vec3d> >& trailMap,
                              QMap<int, int>& trailIndexMap)
1580
{
1581
    QMapIterator<int,int> it(trailIndexMap);
1582

1583
    while (it.hasNext())
Lorenz Meier's avatar
Lorenz Meier committed
1584
    {
1585
        it.next();
1586

1587 1588
        // update trail
        osg::Geometry* geometry = trailNode->getDrawable(it.value() * 2)->asGeometry();
1589 1590 1591 1592
        osg::DrawArrays* drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));

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

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

1595
        vertices->reserve(trail.size());
1596
        for (int i = 0; i < trail.size(); ++i)
Lorenz Meier's avatar
Lorenz Meier committed
1597
        {
1598 1599 1600
            vertices->push_back(osg::Vec3d(trail[i].y() - robotY,
                                           trail[i].x() - robotX,
                                           -(trail[i].z() - robotZ)));
1601 1602
        }

1603 1604 1605 1606
        geometry->setVertexArray(vertices);
        drawArrays->setFirst(0);
        drawArrays->setCount(vertices->size());
        geometry->dirtyBound();
1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638

        // 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();
1639 1640 1641
    }
}

1642
void
1643
Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
1644
                               const QString& zone)
1645
{
1646
    if (mImageryNode->getImageryType() == Imagery::BLANK_MAP)
Lorenz Meier's avatar
Lorenz Meier committed
1647
    {
1648 1649 1650
        return;
    }

1651
    double viewingRadius = m3DWidget->cameraManipulator()->getDistance() * 10.0;
Lorenz Meier's avatar
Lorenz Meier committed
1652 1653
    if (viewingRadius < 100.0)
    {
1654 1655 1656 1657
        viewingRadius = 100.0;
    }

    double minResolution = 0.25;
1658
    double centerResolution = m3DWidget->cameraManipulator()->getDistance() / 50.0;
1659 1660
    double maxResolution = 1048576.0;

1661
    Imagery::Type imageryType = mImageryNode->getImageryType();
Lorenz Meier's avatar
Lorenz Meier committed
1662 1663
    switch (imageryType)
    {
1664 1665 1666 1667 1668 1669 1670 1671 1672 1673
    case Imagery::GOOGLE_MAP:
        minResolution = 0.25;
        break;
    case Imagery::GOOGLE_SATELLITE:
        minResolution = 0.5;
        break;
    case Imagery::SWISSTOPO_SATELLITE:
        minResolution = 0.25;
        maxResolution = 0.25;
        break;
1674
    default:
1675
        {}
1676 1677 1678
    }

    double resolution = minResolution;
Lorenz Meier's avatar
Lorenz Meier committed
1679 1680
    while (resolution * 2.0 < centerResolution)
    {
1681 1682
        resolution *= 2.0;
    }
Lorenz Meier's avatar
Lorenz Meier committed
1683 1684 1685

    if (resolution > maxResolution)
    {
1686 1687 1688
        resolution = maxResolution;
    }

1689 1690 1691 1692 1693 1694 1695 1696
    mImageryNode->draw3D(viewingRadius,
                         resolution,
                         m3DWidget->cameraManipulator()->getCenter().y(),
                         m3DWidget->cameraManipulator()->getCenter().x(),
                         originX,
                         originY,
                         originZ,
                         zone);
1697 1698

    // prefetch map tiles
Lorenz Meier's avatar
Lorenz Meier committed
1699 1700
    if (resolution / 2.0 >= minResolution)
    {
1701 1702 1703 1704 1705
        mImageryNode->prefetch3D(viewingRadius / 2.0,
                                 resolution / 2.0,
                                 m3DWidget->cameraManipulator()->getCenter().y(),
                                 m3DWidget->cameraManipulator()->getCenter().x(),
                                 zone);
1706
    }
Lorenz Meier's avatar
Lorenz Meier committed
1707 1708
    if (resolution * 2.0 <= maxResolution)
    {
1709 1710 1711 1712 1713
        mImageryNode->prefetch3D(viewingRadius * 2.0,
                                 resolution * 2.0,
                                 m3DWidget->cameraManipulator()->getCenter().y(),
                                 m3DWidget->cameraManipulator()->getCenter().x(),
                                 zone);
1714 1715
    }

1716
    mImageryNode->update();
1717
}
1718

1719
void
1720 1721 1722 1723
Pixhawk3DWidget::updateTarget(UASInterface* uas, MAV_FRAME frame,
                              double robotX, double robotY, double robotZ,
                              QVector4D& target,
                              osg::ref_ptr<osg::Node>& targetNode)
1724 1725
{
    osg::PositionAttitudeTransform* pat =
1726 1727
        dynamic_cast<osg::PositionAttitudeTransform*>(targetNode.get());

1728 1729 1730 1731
    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),
1732 1733 1734 1735 1736
                               M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f),
                               0.0, osg::Vec3d(0.0f, 0.0f, 1.0f)));

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

1739
void
1740 1741
Pixhawk3DWidget::updateWaypoints(UASInterface* uas, MAV_FRAME frame,
                                 osg::ref_ptr<WaypointGroupNode>& waypointGroupNode)
1742
{
1743
    waypointGroupNode->update(uas, frame);
1744
}
1745

1746 1747
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)

1748
void
1749 1750 1751
Pixhawk3DWidget::updateObstacles(UASInterface* uas, MAV_FRAME frame,
                                 double robotX, double robotY, double robotZ,
                                 osg::ref_ptr<ObstacleGroupNode>& obstacleGroupNode)
1752
{
1753 1754 1755 1756 1757 1758 1759 1760 1761 1762
    if (frame == MAV_FRAME_GLOBAL)
    {
        obstacleGroupNode->clear();
        return;
    }

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

    if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout)
1763
    {
1764
        obstacleGroupNode->update(robotX, robotY, robotZ, obstacleList);
1765 1766 1767 1768 1769
    }
    else
    {
        obstacleGroupNode->clear();
    }
1770 1771
}

1772
void
1773 1774 1775
Pixhawk3DWidget::updatePlannedPath(UASInterface* uas, MAV_FRAME frame,
                                   double robotX, double robotY, double robotZ,
                                   osg::ref_ptr<osg::Geode>& plannedPathNode)
1776
{
1777 1778
    qreal receivedTimestamp;
    px::Path path = uas->getPath(receivedTimestamp);
1779

1780
    osg::Geometry* geometry = plannedPathNode->getDrawable(0)->asGeometry();
1781
    osg::DrawArrays* drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));
1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792
    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);

1793
    if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout)
1794
    {
1795 1796 1797 1798 1799 1800
        // 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);
1801

1802 1803 1804 1805
            length += qgc::hypot3f(wp0.x() - wp1.x(),
                                   wp0.y() - wp1.y(),
                                   wp0.z() - wp1.z());
        }
1806

1807 1808 1809 1810
        // build path
        if (path.waypoints_size() > 0)
        {
            const px::Waypoint& wp0 = path.waypoints(0);
1811

1812 1813 1814
            vertices->push_back(osg::Vec3d(wp0.y() - robotY,
                                           wp0.x() - robotX,
                                           -(wp0.z() - robotZ)));
1815

1816 1817 1818 1819
            float r, g, b;
            qgc::colormap("autumn", 0, r, g, b);
            colorArray->push_back(osg::Vec4d(r, g, b, 1.0f));
        }
1820

1821 1822 1823 1824 1825
        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);
1826

1827 1828 1829
            lengthCurrent += qgc::hypot3f(wp0.x() - wp1.x(),
                                          wp0.y() - wp1.y(),
                                          wp0.z() - wp1.z());
1830

1831 1832 1833
            vertices->push_back(osg::Vec3d(wp1.y() - robotY,
                                           wp1.x() - robotX,
                                           -(wp1.z() - robotZ)));
1834

1835
            int colorIdx = lengthCurrent / length * 127.0f;
1836

1837 1838 1839 1840
            float r, g, b;
            qgc::colormap("autumn", colorIdx, r, g, b);
            colorArray->push_back(osg::Vec4f(r, g, b, 1.0f));
        }
1841 1842
    }

1843
    geometry->setVertexArray(vertices);
1844 1845 1846 1847 1848
    drawArrays->setFirst(0);
    drawArrays->setCount(vertices->size());
    geometry->dirtyBound();
}

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 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 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 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960
void
Pixhawk3DWidget::updateRGBD(UASInterface* uas, MAV_FRAME frame,
                            osg::ref_ptr<ImageWindowGeode>& rgbImageNode,
                            osg::ref_ptr<ImageWindowGeode>& depthImageNode)
{
    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)
{
    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());
    }
}

1961
#endif
1962

1963
int
1964
Pixhawk3DWidget::findWaypoint(const QPoint& mousePos)
1965
{
1966
    if (!m3DWidget->getSceneData() || !mActiveUAS)
1967
    {
1968 1969
        return -1;
    }
1970

1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983
    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++)
1984
        {
1985
            for (uint i = 0 ; i < it->nodePath.size(); ++i)
1986
            {
1987 1988 1989
                osg::Node* node = it->nodePath[i];
                std::string nodeName = node->getName();
                if (nodeName.substr(0, 2).compare("wp") == 0)
1990
                {
1991
                    if (node->getParent(0)->getParent(0) == waypointGroupNode.get())
1992
                    {
1993
                        return atoi(nodeName.substr(2).c_str());
1994 1995 1996 1997 1998 1999 2000 2001 2002
                    }
                }
            }
        }
    }

    return -1;
}

2003 2004 2005
bool
Pixhawk3DWidget::findTarget(int mouseX, int mouseY)
{
2006
    if (m3DWidget->getSceneData())
2007
    {
2008 2009
        osgUtil::LineSegmentIntersector::Intersections intersections;

2010
        if (m3DWidget->computeIntersections(mouseX, height() - mouseY, intersections))
2011
        {
2012
            for (osgUtil::LineSegmentIntersector::Intersections::iterator
2013 2014 2015 2016
                    it = intersections.begin(); it != intersections.end(); it++)
            {
                for (uint i = 0 ; i < it->nodePath.size(); ++i)
                {
2017
                    std::string nodeName = it->nodePath[i]->getName();
2018 2019
                    if (nodeName.compare("Target") == 0)
                    {
2020 2021 2022 2023 2024 2025 2026 2027 2028 2029
                        return true;
                    }
                }
            }
        }
    }

    return false;
}

2030 2031 2032 2033 2034 2035
void
Pixhawk3DWidget::showInsertWaypointMenu(const QPoint &cursorPos)
{
    QMenu menu;
    menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
2036
    menu.addAction("Select target", this, SLOT(selectTarget()));
2037 2038 2039 2040 2041 2042 2043 2044 2045
    menu.exec(cursorPos);
}

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

    QString text;
2046
    text = QString("Move waypoint %1").arg(QString::number(mSelectedWpIndex));
2047 2048
    menu.addAction(text, this, SLOT(moveWaypointPosition()));

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

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

2055
    text = QString("Delete waypoint %1").arg(QString::number(mSelectedWpIndex));
2056 2057 2058 2059 2060
    menu.addAction(text, this, SLOT(deleteWaypoint()));

    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
    menu.exec(cursorPos);
}