Pixhawk3DWidget.cc 86.7 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"
47

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

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

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

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

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

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

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

86
    setupHUD();
87

88
    buildLayout();
89

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

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

102
    mViewParamWidget->hide();
103

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

108 109
Pixhawk3DWidget::~Pixhawk3DWidget()
{
110

111 112
}

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

    mActiveUAS = uas;
122

123
    mMode = DEFAULT_MODE;
124 125
}

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

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

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

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

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

159
    emit systemCreatedSignal(uas);
160 161
}

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

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

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

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

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

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

202
        systemData.trailNode()->addDrawable(createTrail(color));
203
        systemData.trailNode()->addDrawable(createLink(uas->getColor()));
204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441
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);
442
    if (setpointGroupNode->getNumChildren() > static_cast<unsigned int>(systemViewParams->setpointHistoryLength()))
443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463
    {
        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);
    }
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612
void
Pixhawk3DWidget::loadTerrainModel(void)
{
    QString filename = QFileDialog::getOpenFileName(this, "Load Terrain Model",
                                                    QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
                                                    tr("Collada (*.dae)"));

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

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

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

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

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

636 637 638 639 640 641 642 643 644 645 646 647 648
#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];

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

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

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

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

681 682
    osg::Vec2d p;

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    waypoint->setYaw(yaw);
}

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

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

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

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

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

void
Pixhawk3DWidget::clearAllWaypoints(void)
{
964
    if (mActiveUAS)
965
    {
966
        const QList<Waypoint *> waypoints =
967
            mActiveUAS->getWaypointManager()->getWaypointEditableList();
968 969
        for (int i = waypoints.size() - 1; i >= 0; --i)
        {
970
            mActiveUAS->getWaypointManager()->removeWaypoint(i);
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 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073
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)));
}

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

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

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

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

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

        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;
1141 1142 1143
            visible = (overlayNode->coordinateFrameType() == px::GLOverlay::GLOBAL) &&
                      displayOverlay &&
                      (QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout);
1144 1145 1146

            allocentricMap->setChildValue(overlayNode, visible);

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

            rollingMap->setChildValue(overlayNode, visible);
        }

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

1191
            setBirdEyeView();
1192 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
            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);

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

        }
        else
        {
            systemData.setpointGroupNode()->removeChildren(0, systemData.setpointGroupNode()->getNumChildren());
        }
1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239
        if (systemViewParams->displayTarget())
        {
            if (systemData.target().isNull())
            {
                systemViewParams->displayTarget() = false;
            }
            else
            {
                updateTarget(uas, frame, x, y, z, systemData.target(),
                             systemData.targetNode());
            }
        }
        if (systemViewParams->displayTrails())
        {
1240
            updateTrails(x, y, z, systemData.trailNode(), systemData.orientationNode(),
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 1270
                         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());
        }
1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284

        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);
        }
1285 1286 1287 1288 1289 1290
#endif
    }

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

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

    layout()->update();
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1431
        if (mMode != DEFAULT_MODE)
1432
        {
1433 1434
            mMode = DEFAULT_MODE;
            event->accept();
1435
        }
1436 1437 1438 1439
    }
    else if (event->button() == Qt::RightButton)
    {
        if (m3DWidget->getSceneData() && mActiveUAS)
1440
        {
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
            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;
1484
            if (mSelectedWpIndex == -1)
1485
            {
1486
                mCachedMousePos = event->pos();
1487

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

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

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

            event->accept();
        }
    }

1529

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

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

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

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

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

    m3DWidget->handleMouseMoveEvent(event);
}

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

    m3DWidget->handleWheelEvent(event);
}

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

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

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

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

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

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

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

1638 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
    // 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());
1678
    }
1679

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

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

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

1699 1700 1701 1702 1703 1704 1705 1706
    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;
1707
    }
1708 1709 1710 1711 1712
    else if (frame == MAV_FRAME_LOCAL_NED)
    {
        x = uas->getLocalX();
        y = uas->getLocalY();
        z = uas->getLocalZ();
1713
    }
1714 1715 1716 1717

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

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

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

1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754
    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();
1755 1756 1757 1758
    }
}

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

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

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

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

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

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

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

    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);
1821 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
    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);
1895 1896 1897 1898 1899 1900 1901
    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);
1902 1903
    coarseStateset->setMode(GL_LINE_SMOOTH, osg::StateAttribute::ON);
    coarseStateset->setMode(GL_BLEND, osg::StateAttribute::ON);
1904
    coarseGeometry->setStateSet(coarseStateset);
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
    // 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);

1940 1941 1942
    return geode;
}

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

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

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

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

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

1967
    return geometry;
1968 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
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;
}

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

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

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

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

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

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

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

    return pat;
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2230 2231 2232 2233
        geometry->setVertexArray(vertices);
        drawArrays->setFirst(0);
        drawArrays->setCount(vertices->size());
        geometry->dirtyBound();
2234 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

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

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

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

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

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

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

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

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

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

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

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

2363
    mImageryNode->update();
2364
}
2365

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

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

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

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

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

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

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

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

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

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

2429
    osg::Geometry* geometry = plannedPathNode->getDrawable(0)->asGeometry();
2430
    osg::DrawArrays* drawArrays = reinterpret_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));
2431 2432 2433 2434 2435 2436 2437 2438 2439 2440 2441
    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);

2442
    if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout)
2443
    {
2444 2445 2446 2447 2448 2449
        // 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);
2450

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

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

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

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

2470 2471 2472 2473 2474
        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);
2475

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

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

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

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

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

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

2505 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
    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)
{
2554 2555
    Q_UNUSED(frame);

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

2614
#endif
2615

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

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

    return -1;
}

2656

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

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

    return false;
}

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

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

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

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

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

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

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

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

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