Pixhawk3DWidget.cc 43.2 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36
///*=====================================================================
//
//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.
 *
 *   @author Lionel Heng <hengli@student.ethz.ch>
 *
 */

#include "Pixhawk3DWidget.h"

#include <sstream>

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

#include "PixhawkCheetahGeode.h"
#include "UASManager.h"
44

45 46 47 48 49
#include "QGC.h"

Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
     : Q3DWidget(parent)
     , uas(NULL)
50 51
     , mode(DEFAULT_MODE)
     , selectedWpIndex(-1)
52 53
     , displayGrid(true)
     , displayTrail(false)
54
     , displayImagery(true)
55
     , displayWaypoints(true)
56 57
     , displayRGBD2D(false)
     , displayRGBD3D(false)
58
     , enableRGBDColor(true)
59
     , enableTarget(false)
60
     , followCamera(true)
61
     , enableFreenect(false)
62
     , frame(MAV_FRAME_GLOBAL)
63 64 65
     , lastRobotX(0.0f)
     , lastRobotY(0.0f)
     , lastRobotZ(0.0f)
66
{
67
    setCameraParams(2.0f, 30.0f, 0.01f, 10000.0f);
68 69 70
    init(15.0f);

    // generate Pixhawk Cheetah model
71 72
    vehicleModel = PixhawkCheetahGeode::instance();
    egocentricMap->addChild(vehicleModel);
73 74 75 76 77 78 79 80 81

    // generate grid model
    gridNode = createGrid();
    rollingMap->addChild(gridNode);

    // generate empty trail model
    trailNode = createTrail();
    rollingMap->addChild(trailNode);

82 83
    // generate map model
    mapNode = createMap();
84
    rollingMap->addChild(mapNode);
85

86
    // generate waypoint model
87 88 89
    waypointGroupNode = new WaypointGroupNode;
    waypointGroupNode->init();
    rollingMap->addChild(waypointGroupNode);
90

91 92 93 94
    // generate target model
    targetNode = createTarget();
    rollingMap->addChild(targetNode);

95 96
#ifdef QGC_LIBFREENECT_ENABLED
    freenect.reset(new Freenect());
97
    enableFreenect = freenect->init();
98 99
#endif

100
    // generate RGBD model
101 102 103 104 105
    if (enableFreenect)
    {
        rgbd3DNode = createRGBD3D();
        egocentricMap->addChild(rgbd3DNode);
    }
106

107 108
    setupHUD();

109 110 111
    // find available vehicle models in models folder
    vehicleModels = findVehicleModels();

112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137
    buildLayout();

    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
            this, SLOT(setActiveUAS(UASInterface*)));
}

Pixhawk3DWidget::~Pixhawk3DWidget()
{

}

/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void Pixhawk3DWidget::setActiveUAS(UASInterface* uas)
{
    if (this->uas != NULL && this->uas != uas)
    {
        // Disconnect any previously connected active MAV
        //disconnect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
    }

    this->uas = uas;
}

138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154
void
Pixhawk3DWidget::selectFrame(QString text)
{
    if (text.compare("Global") == 0)
    {
        frame = MAV_FRAME_GLOBAL;
    }
    else if (text.compare("Local") == 0)
    {
        frame = MAV_FRAME_LOCAL;
    }

    getPosition(lastRobotX, lastRobotY, lastRobotZ);

    recenter();
}

155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174
void
Pixhawk3DWidget::showGrid(int32_t state)
{
    if (state == Qt::Checked)
    {
        displayGrid = true;
    }
    else
    {
        displayGrid = false;
    }
}

void
Pixhawk3DWidget::showTrail(int32_t state)
{
    if (state == Qt::Checked)
    {
        if (!displayTrail)
        {
175
            trail.clear();
176 177 178 179 180 181 182 183 184 185
        }

        displayTrail = true;
    }
    else
    {
        displayTrail = false;
    }
}

186 187 188 189 190 191 192 193 194 195 196 197 198
void
Pixhawk3DWidget::showWaypoints(int state)
{
    if (state == Qt::Checked)
    {
        displayWaypoints = true;
    }
    else
    {
        displayWaypoints = false;
    }
}

199 200 201 202
void
Pixhawk3DWidget::selectMapSource(int index)
{
    mapNode->setImageryType(static_cast<Imagery::ImageryType>(index));
203 204 205 206 207 208 209 210 211

    if (mapNode->getImageryType() == Imagery::BLANK_MAP)
    {
        displayImagery = false;
    }
    else
    {
        displayImagery = true;
    }
212 213
}

214 215 216
void
Pixhawk3DWidget::selectVehicleModel(int index)
{
217
    egocentricMap->removeChild(vehicleModel);
218
    vehicleModel = vehicleModels.at(index);
219
    egocentricMap->addChild(vehicleModel);
220 221
}

222
void
223
Pixhawk3DWidget::recenter(void)
224
{
225
    double robotX = 0.0f, robotY = 0.0f, robotZ = 0.0f;
226
    getPosition(robotX, robotY, robotZ);
227

228
    recenterCamera(robotY, robotX, -robotZ);
229 230 231
}

void
232
Pixhawk3DWidget::toggleFollowCamera(int32_t state)
233 234 235
{
    if (state == Qt::Checked)
    {
236
        followCamera = true;
237 238 239
    }
    else
    {
240
        followCamera = false;
241 242
    }
}
243

244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273
void
Pixhawk3DWidget::selectTarget(void)
{
    if (uas)
    {
        if (frame == MAV_FRAME_GLOBAL)
        {
            double altitude = uas->getAltitude();

            std::pair<double,double> cursorWorldCoords =
                    getGlobalCursorPosition(getMouseX(), getMouseY(), altitude);

            target.set(cursorWorldCoords.first, cursorWorldCoords.second);
        }
        else if (frame == MAV_FRAME_LOCAL)
        {
            double z = uas->getLocalZ();

            std::pair<double,double> cursorWorldCoords =
                    getGlobalCursorPosition(getMouseX(), getMouseY(), -z);

            target.set(cursorWorldCoords.first, cursorWorldCoords.second);
        }

        uas->setTargetPosition(target.x(), target.y(), 0.0, 0.0);

        enableTarget = true;
    }
}

274 275 276 277 278
void
Pixhawk3DWidget::insertWaypoint(void)
{
    if (uas)
    {
279
        Waypoint* wp = NULL;
280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310
        if (frame == MAV_FRAME_GLOBAL)
        {
            double latitude = uas->getLatitude();
            double longitude = uas->getLongitude();
            double altitude = uas->getAltitude();
            double x, y;
            QString utmZone;
            Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

            std::pair<double,double> cursorWorldCoords =
                    getGlobalCursorPosition(getMouseX(), getMouseY(), altitude);

            Imagery::UTMtoLL(cursorWorldCoords.first, cursorWorldCoords.second, utmZone,
                             latitude, longitude);

            wp = new Waypoint(0, longitude, latitude, altitude);
        }
        else if (frame == MAV_FRAME_LOCAL)
        {
            double z = uas->getLocalZ();

            std::pair<double,double> cursorWorldCoords =
                    getGlobalCursorPosition(getMouseX(), getMouseY(), -z);

            wp = new Waypoint(0, cursorWorldCoords.first,
                              cursorWorldCoords.second, z);
        }

        if (wp)
        {
            wp->setFrame(frame);
311
            uas->getWaypointManager()->addWaypoint(wp);
312
        }
313 314 315 316 317 318 319 320 321 322 323 324 325 326 327
    }
}

void
Pixhawk3DWidget::moveWaypoint(void)
{
    mode = MOVE_WAYPOINT_MODE;
}

void
Pixhawk3DWidget::setWaypoint(void)
{
    if (uas)
    {
        const QVector<Waypoint *> waypoints =
328
                uas->getWaypointManager()->getWaypointList();
329
        Waypoint* waypoint = waypoints.at(selectedWpIndex);
330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360

        if (frame == MAV_FRAME_GLOBAL)
        {
            double latitude = uas->getLatitude();
            double longitude = uas->getLongitude();
            double altitude = uas->getAltitude();
            double x, y;
            QString utmZone;
            Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);

            std::pair<double,double> cursorWorldCoords =
                    getGlobalCursorPosition(getMouseX(), getMouseY(), altitude);

            Imagery::UTMtoLL(cursorWorldCoords.first, cursorWorldCoords.second, utmZone,
                             latitude, longitude);

            waypoint->setX(longitude);
            waypoint->setY(latitude);
            waypoint->setZ(altitude);
        }
        else if (frame == MAV_FRAME_LOCAL)
        {
            double z = uas->getLocalZ();

            std::pair<double,double> cursorWorldCoords =
                    getGlobalCursorPosition(getMouseX(), getMouseY(), -z);

            waypoint->setX(cursorWorldCoords.first);
            waypoint->setY(cursorWorldCoords.second);
            waypoint->setZ(z);
        }
361 362 363 364 365 366 367 368
    }
}

void
Pixhawk3DWidget::deleteWaypoint(void)
{
    if (uas)
    {
369
        uas->getWaypointManager()->removeWaypoint(selectedWpIndex);
370 371 372 373 374 375 376 377
    }
}

void
Pixhawk3DWidget::setWaypointAltitude(void)
{
    if (uas)
    {
378
        bool ok;
379
        const QVector<Waypoint *> waypoints =
380
                uas->getWaypointManager()->getWaypointList();
381 382
        Waypoint* waypoint = waypoints.at(selectedWpIndex);

383 384 385 386 387 388
        double altitude = waypoint->getZ();
        if (frame == MAV_FRAME_LOCAL)
        {
            altitude = -altitude;
        }

389 390
        double newAltitude =
                QInputDialog::getDouble(this, tr("Set altitude of waypoint %1").arg(selectedWpIndex),
391
                                        tr("Altitude (m):"), waypoint->getZ(), -1000.0, 1000.0, 1, &ok);
392 393
        if (ok)
        {
394 395 396 397 398 399 400 401
            if (frame == MAV_FRAME_GLOBAL)
            {
                waypoint->setZ(newAltitude);
            }
            else if (frame == MAV_FRAME_LOCAL)
            {
                waypoint->setZ(-newAltitude);
            }
402
        }
403 404 405 406 407 408 409 410
    }
}

void
Pixhawk3DWidget::clearAllWaypoints(void)
{
    if (uas)
    {
411
        const QVector<Waypoint *> waypoints =
412
                uas->getWaypointManager()->getWaypointList();
413 414
        for (int i = waypoints.size() - 1; i >= 0; --i)
        {
415
            uas->getWaypointManager()->removeWaypoint(i);
416
        }
417 418 419
    }
}

420 421 422 423
QVector< osg::ref_ptr<osg::Node> >
Pixhawk3DWidget::findVehicleModels(void)
{
    QDir directory("models");
lm's avatar
lm committed
424
    QStringList files = directory.entryList(QStringList("*.osg"), QDir::Files);
425 426 427 428

    QVector< osg::ref_ptr<osg::Node> > nodes;

    // add Pixhawk Bravo model
429
    nodes.push_back(PixhawkCheetahGeode::instance());
430

hengli's avatar
hengli committed
431 432 433
    // 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);
434
    sphereDrawable->setColor(osg::Vec4f(0.5f, 0.0f, 0.5f, 1.0f));
hengli's avatar
hengli committed
435 436 437 438 439
    osg::ref_ptr<osg::Geode> sphereGeode = new osg::Geode;
    sphereGeode->addDrawable(sphereDrawable);
    sphereGeode->setName("Sphere (0.1m)");
    nodes.push_back(sphereGeode);

440
    // add all other models in folder
441 442 443 444 445
    for (int i = 0; i < files.size(); ++i)
    {
        osg::ref_ptr<osg::Node> node =
                osgDB::readNodeFile(directory.absoluteFilePath(files[i]).toStdString().c_str());

lm's avatar
lm committed
446 447
        if (node)
        {
448
            nodes.push_back(node);
lm's avatar
lm committed
449 450 451
        }
        else
        {
452
            printf("%s\n", QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
lm's avatar
lm committed
453
        }
454 455
    }

lm's avatar
lm committed
456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477
//    QStringList dirs = directory.entryList(QDir::Dirs);
//    // Add models in subfolders
//    for (int i = 0; i < dirs.size(); ++i)
//    {
//        // Handling the current directory
//        QStringList currFiles = QDir(dirs[i]).entryList(QStringList("*.ac"), QDir::Files);

//        // Load the file
//        osg::ref_ptr<osg::Node> node =
//                osgDB::readNodeFile(directory.absoluteFilePath(currFiles.first()).toStdString().c_str());

//        if (node)
//        {

//        nodes.push_back(node);
//        }
//        else
//        {
//            printf(QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
//        }
//    }

478 479 480 481 482 483
    return nodes;
}

void
Pixhawk3DWidget::buildLayout(void)
{
484 485 486 487 488
    QComboBox* frameComboBox = new QComboBox(this);
    frameComboBox->addItem("Global");
    frameComboBox->addItem("Local");
    frameComboBox->setFixedWidth(70);

489 490 491 492 493 494 495 496 497 498 499 500
    QCheckBox* gridCheckBox = new QCheckBox(this);
    gridCheckBox->setText("Grid");
    gridCheckBox->setChecked(displayGrid);

    QCheckBox* trailCheckBox = new QCheckBox(this);
    trailCheckBox->setText("Trail");
    trailCheckBox->setChecked(displayTrail);

    QCheckBox* waypointsCheckBox = new QCheckBox(this);
    waypointsCheckBox->setText("Waypoints");
    waypointsCheckBox->setChecked(displayWaypoints);

501 502 503 504 505 506
    QLabel* mapLabel = new QLabel("Map", this);
    QComboBox* mapComboBox = new QComboBox(this);
    mapComboBox->addItem("None");
    mapComboBox->addItem("Map (Google)");
    mapComboBox->addItem("Satellite (Google)");

507
    QLabel* modelLabel = new QLabel("Vehicle", this);
508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523
    QComboBox* modelComboBox = new QComboBox(this);
    for (int i = 0; i < vehicleModels.size(); ++i)
    {
        modelComboBox->addItem(vehicleModels[i]->getName().c_str());
    }

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

    QCheckBox* followCameraCheckBox = new QCheckBox(this);
    followCameraCheckBox->setText("Follow Camera");
    followCameraCheckBox->setChecked(followCamera);

    QGridLayout* layout = new QGridLayout(this);
    layout->setMargin(0);
    layout->setSpacing(2);
524 525 526 527 528 529 530 531 532 533 534 535 536 537 538
    layout->addWidget(frameComboBox, 0, 10);
    layout->addWidget(gridCheckBox, 2, 0);
    layout->addWidget(trailCheckBox, 2, 1);
    layout->addWidget(waypointsCheckBox, 2, 2);
    layout->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 2, 3);
    layout->addWidget(mapLabel, 2, 4);
    layout->addWidget(mapComboBox, 2, 5);
    layout->addWidget(modelLabel, 2, 6);
    layout->addWidget(modelComboBox, 2, 7);
    layout->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 2, 8);
    layout->addWidget(recenterButton, 2, 9);
    layout->addWidget(followCameraCheckBox, 2, 10);
    layout->setRowStretch(0, 1);
    layout->setRowStretch(1, 100);
    layout->setRowStretch(2, 1);
539 540
    setLayout(layout);

541 542
    connect(frameComboBox, SIGNAL(currentIndexChanged(QString)),
            this, SLOT(selectFrame(QString)));
543 544 545 546 547 548
    connect(gridCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(showGrid(int)));
    connect(trailCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(showTrail(int)));
    connect(waypointsCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(showWaypoints(int)));
549 550
    connect(mapComboBox, SIGNAL(currentIndexChanged(int)),
            this, SLOT(selectMapSource(int)));
551 552 553 554 555 556
    connect(modelComboBox, SIGNAL(currentIndexChanged(int)),
            this, SLOT(selectVehicleModel(int)));
    connect(recenterButton, SIGNAL(clicked()), this, SLOT(recenter()));
    connect(followCameraCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(toggleFollowCamera(int)));
}
557

558 559 560
void
Pixhawk3DWidget::display(void)
{
561
    if (uas == NULL)
562
    {
563 564 565
        return;
    }

566
    double robotX, robotY, robotZ, robotRoll, robotPitch, robotYaw;
567
    QString utmZone;
568
    getPose(robotX, robotY, robotZ, robotRoll, robotPitch, robotYaw, utmZone);
569 570 571 572 573 574 575 576

    if (lastRobotX == 0.0f && lastRobotY == 0.0f && lastRobotZ == 0.0f)
    {
        lastRobotX = robotX;
        lastRobotY = robotY;
        lastRobotZ = robotZ;

        recenterCamera(robotY, robotX, -robotZ);
577 578
    }

579 580
    if (followCamera)
    {
581 582 583
        double dx = robotY - lastRobotY;
        double dy = robotX - lastRobotX;
        double dz = lastRobotZ - robotZ;
584 585

        moveCamera(dx, dy, dz);
586 587
    }

588 589 590 591
    robotPosition->setPosition(osg::Vec3d(robotY, robotX, -robotZ));
    robotAttitude->setAttitude(osg::Quat(-robotYaw, osg::Vec3d(0.0f, 0.0f, 1.0f),
                                         robotPitch, osg::Vec3d(1.0f, 0.0f, 0.0f),
                                         robotRoll, osg::Vec3d(0.0f, 1.0f, 0.0f)));
592

593 594 595 596 597
    if (displayTrail)
    {
        updateTrail(robotX, robotY, robotZ);
    }

598
    if (frame == MAV_FRAME_GLOBAL && displayImagery)
599
    {
600
        updateImagery(robotX, robotY, robotZ, utmZone);
601 602 603 604 605 606 607
    }

    if (displayWaypoints)
    {
        updateWaypoints();
    }

608 609 610 611 612
    if (enableTarget)
    {
        updateTarget(robotX, robotY);
    }

613
#ifdef QGC_LIBFREENECT_ENABLED
614
    if (enableFreenect && (displayRGBD2D || displayRGBD3D))
615 616 617
    {
        updateRGBD();
    }
618
#endif
619
    updateHUD(robotX, robotY, robotZ, robotRoll, robotPitch, robotYaw, utmZone);
620 621

    // set node visibility
622

623 624
    rollingMap->setChildValue(gridNode, displayGrid);
    rollingMap->setChildValue(trailNode, displayTrail);
625
    rollingMap->setChildValue(mapNode, displayImagery);
626
    rollingMap->setChildValue(waypointGroupNode, displayWaypoints);
627
    rollingMap->setChildValue(targetNode, enableTarget);
628 629 630 631
    if (enableFreenect)
    {
        egocentricMap->setChildValue(rgbd3DNode, displayRGBD3D);
    }
632 633
    hudGroup->setChildValue(rgb2DGeode, displayRGBD2D);
    hudGroup->setChildValue(depth2DGeode, displayRGBD2D);
634 635 636 637

    lastRobotX = robotX;
    lastRobotY = robotY;
    lastRobotZ = robotZ;
638 639
}

640 641 642 643 644 645 646 647 648 649
void
Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
{
    if (!event->text().isEmpty())
    {
        switch (*(event->text().toAscii().data()))
        {
        case '1':
            displayRGBD2D = !displayRGBD2D;
            break;
650 651 652
        case '2':
            displayRGBD3D = !displayRGBD3D;
            break;
653 654 655
        case 'c': case 'C':
            enableRGBDColor = !enableRGBDColor;
            break;
656 657 658 659 660 661
        }
    }

    Q3DWidget::keyPressEvent(event);
}

662 663 664
void
Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
{
665
    if (event->button() == Qt::LeftButton)
666
    {
667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688
        if (mode == MOVE_WAYPOINT_MODE)
        {
            setWaypoint();
            mode = DEFAULT_MODE;

            return;
        }

        if (event->modifiers() == Qt::ShiftModifier)
        {
            selectedWpIndex = findWaypoint(event->x(), event->y());
            if (selectedWpIndex == -1)
            {
                showInsertWaypointMenu(event->globalPos());
            }
            else
            {
                showEditWaypointMenu(event->globalPos());
            }

            return;
        }
689 690 691 692 693
    }

    Q3DWidget::mousePressEvent(event);
}

694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762
void
Pixhawk3DWidget::getPose(double& x, double& y, double& z,
                         double& roll, double& pitch, double& yaw,
                         QString& utmZone)
{
    if (uas)
    {
        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)
        {
            x = uas->getLocalX();
            y = uas->getLocalY();
            z = uas->getLocalZ();
        }


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

void
Pixhawk3DWidget::getPose(double& x, double& y, double& z,
                         double& roll, double& pitch, double& yaw)
{
    QString utmZone;
    getPose(x, y, z, roll, pitch, yaw);
}

void
Pixhawk3DWidget::getPosition(double& x, double& y, double& z,
                             QString& utmZone)
{
    if (uas)
    {
        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)
        {
            x = uas->getLocalX();
            y = uas->getLocalY();
            z = uas->getLocalZ();
        }
    }
}

void
Pixhawk3DWidget::getPosition(double& x, double& y, double& z)
{
    QString utmZone;
    getPosition(x, y, z, utmZone);
}

763 764 765 766
osg::ref_ptr<osg::Geode>
Pixhawk3DWidget::createGrid(void)
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
767 768 769 770
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
771 772 773 774

    float radius = 10.0f;
    float resolution = 0.25f;

775 776
    osg::ref_ptr<osg::Vec3Array> fineCoords(new osg::Vec3Array);
    osg::ref_ptr<osg::Vec3Array> coarseCoords(new osg::Vec3Array);
777 778 779 780

    // draw a 20m x 20m grid with 0.25m resolution
    for (float i = -radius; i <= radius; i += resolution)
    {
pixhawk's avatar
pixhawk committed
781
        if (fabsf(i - floor(i + 0.5f)) < 0.01f)
782 783 784 785 786 787 788 789 790 791 792 793 794
        {
            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));
        }
795 796
    }

797 798
    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);
799 800 801

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824
    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.25f);
    fineStateset->setAttributeAndModes(fineLinewidth, osg::StateAttribute::ON);
    fineStateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
    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);
    coarseGeometry->setStateSet(coarseStateset);
825 826 827 828 829 830 831 832 833 834 835 836

    return geode;
}

osg::ref_ptr<osg::Geode>
Pixhawk3DWidget::createTrail(void)
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
    trailGeometry = new osg::Geometry();
    trailGeometry->setUseDisplayList(false);
    geode->addDrawable(trailGeometry.get());

837
    trailVertices = new osg::Vec3dArray;
838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857
    trailGeometry->setVertexArray(trailVertices);

    trailDrawArrays = new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP);
    trailGeometry->addPrimitiveSet(trailDrawArrays);

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(1.0f, 0.0f, 0.0f, 1.0f));
    trailGeometry->setColorArray(color);
    trailGeometry->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(1.0f);
    stateset->setAttributeAndModes(linewidth, osg::StateAttribute::ON);
    stateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
    trailGeometry->setStateSet(stateset);

    return geode;
}

858
osg::ref_ptr<Imagery>
859 860
Pixhawk3DWidget::createMap(void)
{
861
    return osg::ref_ptr<Imagery>(new Imagery());
862 863
}

864
osg::ref_ptr<osg::Geode>
865
Pixhawk3DWidget::createRGBD3D(void)
866
{
867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882
    int frameSize = 640 * 480;

    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;
883 884
}

885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904
osg::ref_ptr<osg::Node>
Pixhawk3DWidget::createTarget(void)
{
    osg::ref_ptr<osg::PositionAttitudeTransform> pat =
            new osg::PositionAttitudeTransform;

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

    osg::ref_ptr<osg::Sphere> sphere = new osg::Sphere(osg::Vec3f(0.0f, 0.0f, 0.0f), 0.1f);
    osg::ref_ptr<osg::ShapeDrawable> sphereDrawable = new osg::ShapeDrawable(sphere);
    sphereDrawable->setColor(osg::Vec4f(0.0f, 1.0f, 0.0f, 1.0f));
    osg::ref_ptr<osg::Geode> sphereGeode = new osg::Geode;
    sphereGeode->addDrawable(sphereDrawable);
    sphereGeode->setName("Target");

    pat->addChild(sphereGeode);

    return pat;
}

905 906 907 908
void
Pixhawk3DWidget::setupHUD(void)
{
    osg::ref_ptr<osg::Vec4Array> hudColors(new osg::Vec4Array);
909 910
    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));
911 912

    hudBackgroundGeometry = new osg::Geometry;
913 914 915 916
    hudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                                               0, 4));
    hudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                                               4, 4));
917
    hudBackgroundGeometry->setColorArray(hudColors);
918
    hudBackgroundGeometry->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
919
    hudBackgroundGeometry->setUseDisplayList(false);
920 921 922 923 924 925 926

    statusText = new osgText::Text;
    statusText->setCharacterSize(11);
    statusText->setFont("images/Vera.ttf");
    statusText->setAxisAlignment(osgText::Text::SCREEN);
    statusText->setColor(osg::Vec4(255, 255, 255, 1));

927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944
    resizeHUD();

    osg::ref_ptr<osg::Geode> statusGeode = new osg::Geode;
    statusGeode->addDrawable(hudBackgroundGeometry);
    statusGeode->addDrawable(statusText);
    hudGroup->addChild(statusGeode);

    rgbImage = new osg::Image;
    rgb2DGeode = new ImageWindowGeode("RGB Image",
                                      osg::Vec4(0.0f, 0.0f, 0.1f, 1.0f),
                                      rgbImage);
    hudGroup->addChild(rgb2DGeode);

    depthImage = new osg::Image;
    depth2DGeode = new ImageWindowGeode("Depth Image",
                                        osg::Vec4(0.0f, 0.0f, 0.1f, 1.0f),
                                        depthImage);
    hudGroup->addChild(depth2DGeode);
945 946 947 948

    scaleGeode = new HUDScaleGeode;
    scaleGeode->init();
    hudGroup->addChild(scaleGeode);
949 950 951
}

void
952
Pixhawk3DWidget::resizeHUD(void)
953
{
954
    int topHUDHeight = 25;
955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973
    int bottomHUDHeight = 25;

    osg::Vec3Array* vertices = static_cast<osg::Vec3Array*>(hudBackgroundGeometry->getVertexArray());
    if (vertices == NULL || vertices->size() != 8)
    {
        osg::ref_ptr<osg::Vec3Array> newVertices = new osg::Vec3Array(8);
        hudBackgroundGeometry->setVertexArray(newVertices);

        vertices = static_cast<osg::Vec3Array*>(hudBackgroundGeometry->getVertexArray());
    }

    (*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);
    (*vertices)[4] = osg::Vec3(0, 0, -1);
    (*vertices)[5] = osg::Vec3(width(), 0, -1);
    (*vertices)[6] = osg::Vec3(width(), bottomHUDHeight, -1);
    (*vertices)[7] = osg::Vec3(0, bottomHUDHeight, -1);
974

975
    statusText->setPosition(osg::Vec3(10, height() - 15, -1.5));
976

977 978 979 980 981 982 983 984 985 986 987 988
    if (rgb2DGeode.valid() && depth2DGeode.valid())
    {
        int windowWidth = (width() - 20) / 2;
        int windowHeight = 3 * windowWidth / 4;
        rgb2DGeode->setAttributes(10, (height() - windowHeight) / 2,
                                  windowWidth, windowHeight);
        depth2DGeode->setAttributes(width() / 2, (height() - windowHeight) / 2,
                                    windowWidth, windowHeight);
    }
}

void
989
Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ,
990 991
                           double robotRoll, double robotPitch, double robotYaw,
                           const QString& utmZone)
992 993 994
{
    resizeHUD();

995 996
    std::pair<double,double> cursorPosition =
            getGlobalCursorPosition(getMouseX(), getMouseY(), -robotZ);
997 998 999 1000

    std::ostringstream oss;
    oss.setf(std::ios::fixed, std::ios::floatfield);
    oss.precision(2);
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
    if (frame == MAV_FRAME_GLOBAL)
    {
        double latitude, longitude;
        Imagery::UTMtoLL(robotX, robotY, utmZone, latitude, longitude);

        double cursorLatitude, cursorLongitude;
        Imagery::UTMtoLL(cursorPosition.first, cursorPosition.second,
                         utmZone, cursorLatitude, cursorLongitude);

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

        oss.precision(2);
        oss << " Altitude = " << -robotZ <<
                " r = " << robotRoll <<
                " p = " << robotPitch <<
                " y = " << robotYaw;

        oss.precision(6);
        oss << " Cursor [" << cursorLatitude <<
                " " << cursorLongitude << "]";
    }
    else if (frame == MAV_FRAME_LOCAL)
    {
        oss << " x = " << robotX <<
                " y = " << robotY <<
                " z = " << robotZ <<
                " r = " << robotRoll <<
                " p = " << robotPitch <<
                " y = " << robotYaw <<
                " Cursor [" << cursorPosition.first <<
                " " << cursorPosition.second << "]";
    }

1036
    statusText->setText(oss.str());
1037

1038 1039 1040 1041 1042 1043 1044 1045
    bool darkBackground = true;
    if (mapNode->getImageryType() == Imagery::GOOGLE_MAP)
    {
        darkBackground = false;
    }

    scaleGeode->update(height(), cameraParams.cameraFov,
                       cameraManipulator->getDistance(), darkBackground);
1046 1047 1048
}

void
1049
Pixhawk3DWidget::updateTrail(double robotX, double robotY, double robotZ)
1050 1051 1052 1053 1054 1055 1056 1057 1058
{
    if (robotX == 0.0f || robotY == 0.0f || robotZ == 0.0f)
    {
        return;
    }

    bool addToTrail = false;
    if (trail.size() > 0)
    {
1059 1060 1061
        if (fabs(robotX - trail[trail.size() - 1].x()) > 0.01f ||
            fabs(robotY - trail[trail.size() - 1].y()) > 0.01f ||
            fabs(robotZ - trail[trail.size() - 1].z()) > 0.01f)
1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072
        {
            addToTrail = true;
        }
    }
    else
    {
        addToTrail = true;
    }

    if (addToTrail)
    {
1073
        osg::Vec3d p(robotX, robotY, robotZ);
1074 1075 1076
        if (trail.size() == trail.capacity())
        {
            memcpy(trail.data(), trail.data() + 1,
1077
                   (trail.size() - 1) * sizeof(osg::Vec3d));
1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088
            trail[trail.size() - 1] = p;
        }
        else
        {
            trail.append(p);
        }
    }

    trailVertices->clear();
    for (int i = 0; i < trail.size(); ++i)
    {
1089 1090 1091
        trailVertices->push_back(osg::Vec3d(trail[i].y() - robotY,
                                            trail[i].x() - robotX,
                                            -(trail[i].z() - robotZ)));
1092 1093 1094 1095 1096 1097 1098
    }

    trailDrawArrays->setFirst(0);
    trailDrawArrays->setCount(trailVertices->size());
    trailGeometry->dirtyBound();
}

1099
void
1100
Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
1101
                               const QString& zone)
1102
{
1103 1104 1105 1106 1107
    if (mapNode->getImageryType() == Imagery::BLANK_MAP)
    {
        return;
    }

1108 1109 1110 1111 1112 1113 1114
    double viewingRadius = cameraManipulator->getDistance() * 10.0;
    if (viewingRadius < 100.0)
    {
        viewingRadius = 100.0;
    }

    double minResolution = 0.25;
1115
    double centerResolution = cameraManipulator->getDistance() / 50.0;
1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147
    double maxResolution = 1048576.0;

    Imagery::ImageryType imageryType = mapNode->getImageryType();
    switch (imageryType)
    {
    case Imagery::GOOGLE_MAP:
        minResolution = 0.25;
        break;
    case Imagery::GOOGLE_SATELLITE:
        minResolution = 0.5;
        break;
    case Imagery::SWISSTOPO_SATELLITE:
        minResolution = 0.25;
        maxResolution = 0.25;
        break;
    default: {}
    }

    double resolution = minResolution;
    while (resolution * 2.0 < centerResolution)
    {
        resolution *= 2.0;
    }
    if (resolution > maxResolution)
    {
        resolution = maxResolution;
    }

    mapNode->draw3D(viewingRadius,
                    resolution,
                    cameraManipulator->getCenter().y(),
                    cameraManipulator->getCenter().x(),
1148 1149
                    originX,
                    originY,
1150
                    originZ,
1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173
                    zone);

    // prefetch map tiles
    if (resolution / 2.0 >= minResolution)
    {
        mapNode->prefetch3D(viewingRadius / 2.0,
                            resolution / 2.0,
                            cameraManipulator->getCenter().y(),
                            cameraManipulator->getCenter().x(),
                            zone);
    }
    if (resolution * 2.0 <= maxResolution)
    {
        mapNode->prefetch3D(viewingRadius * 2.0,
                            resolution * 2.0,
                            cameraManipulator->getCenter().y(),
                            cameraManipulator->getCenter().x(),
                            zone);
    }

    mapNode->update();
}

1174 1175 1176
void
Pixhawk3DWidget::updateWaypoints(void)
{
1177
    waypointGroupNode->update(frame, uas);
1178
}
1179

1180 1181 1182 1183 1184 1185 1186 1187
void
Pixhawk3DWidget::updateTarget(double robotX, double robotY)
{
    osg::PositionAttitudeTransform* pat =
            static_cast<osg::PositionAttitudeTransform*>(targetNode.get());
    pat->setPosition(osg::Vec3d(target.y() - robotY, target.x() - robotX, 0.0));
}

1188 1189 1190 1191 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 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319
float colormap_jet[128][3] =
{
                {0.0f,0.0f,0.53125f},
                {0.0f,0.0f,0.5625f},
                {0.0f,0.0f,0.59375f},
                {0.0f,0.0f,0.625f},
                {0.0f,0.0f,0.65625f},
                {0.0f,0.0f,0.6875f},
                {0.0f,0.0f,0.71875f},
                {0.0f,0.0f,0.75f},
                {0.0f,0.0f,0.78125f},
                {0.0f,0.0f,0.8125f},
                {0.0f,0.0f,0.84375f},
                {0.0f,0.0f,0.875f},
                {0.0f,0.0f,0.90625f},
                {0.0f,0.0f,0.9375f},
                {0.0f,0.0f,0.96875f},
                {0.0f,0.0f,1.0f},
                {0.0f,0.03125f,1.0f},
                {0.0f,0.0625f,1.0f},
                {0.0f,0.09375f,1.0f},
                {0.0f,0.125f,1.0f},
                {0.0f,0.15625f,1.0f},
                {0.0f,0.1875f,1.0f},
                {0.0f,0.21875f,1.0f},
                {0.0f,0.25f,1.0f},
                {0.0f,0.28125f,1.0f},
                {0.0f,0.3125f,1.0f},
                {0.0f,0.34375f,1.0f},
                {0.0f,0.375f,1.0f},
                {0.0f,0.40625f,1.0f},
                {0.0f,0.4375f,1.0f},
                {0.0f,0.46875f,1.0f},
                {0.0f,0.5f,1.0f},
                {0.0f,0.53125f,1.0f},
                {0.0f,0.5625f,1.0f},
                {0.0f,0.59375f,1.0f},
                {0.0f,0.625f,1.0f},
                {0.0f,0.65625f,1.0f},
                {0.0f,0.6875f,1.0f},
                {0.0f,0.71875f,1.0f},
                {0.0f,0.75f,1.0f},
                {0.0f,0.78125f,1.0f},
                {0.0f,0.8125f,1.0f},
                {0.0f,0.84375f,1.0f},
                {0.0f,0.875f,1.0f},
                {0.0f,0.90625f,1.0f},
                {0.0f,0.9375f,1.0f},
                {0.0f,0.96875f,1.0f},
                {0.0f,1.0f,1.0f},
                {0.03125f,1.0f,0.96875f},
                {0.0625f,1.0f,0.9375f},
                {0.09375f,1.0f,0.90625f},
                {0.125f,1.0f,0.875f},
                {0.15625f,1.0f,0.84375f},
                {0.1875f,1.0f,0.8125f},
                {0.21875f,1.0f,0.78125f},
                {0.25f,1.0f,0.75f},
                {0.28125f,1.0f,0.71875f},
                {0.3125f,1.0f,0.6875f},
                {0.34375f,1.0f,0.65625f},
                {0.375f,1.0f,0.625f},
                {0.40625f,1.0f,0.59375f},
                {0.4375f,1.0f,0.5625f},
                {0.46875f,1.0f,0.53125f},
                {0.5f,1.0f,0.5f},
                {0.53125f,1.0f,0.46875f},
                {0.5625f,1.0f,0.4375f},
                {0.59375f,1.0f,0.40625f},
                {0.625f,1.0f,0.375f},
                {0.65625f,1.0f,0.34375f},
                {0.6875f,1.0f,0.3125f},
                {0.71875f,1.0f,0.28125f},
                {0.75f,1.0f,0.25f},
                {0.78125f,1.0f,0.21875f},
                {0.8125f,1.0f,0.1875f},
                {0.84375f,1.0f,0.15625f},
                {0.875f,1.0f,0.125f},
                {0.90625f,1.0f,0.09375f},
                {0.9375f,1.0f,0.0625f},
                {0.96875f,1.0f,0.03125f},
                {1.0f,1.0f,0.0f},
                {1.0f,0.96875f,0.0f},
                {1.0f,0.9375f,0.0f},
                {1.0f,0.90625f,0.0f},
                {1.0f,0.875f,0.0f},
                {1.0f,0.84375f,0.0f},
                {1.0f,0.8125f,0.0f},
                {1.0f,0.78125f,0.0f},
                {1.0f,0.75f,0.0f},
                {1.0f,0.71875f,0.0f},
                {1.0f,0.6875f,0.0f},
                {1.0f,0.65625f,0.0f},
                {1.0f,0.625f,0.0f},
                {1.0f,0.59375f,0.0f},
                {1.0f,0.5625f,0.0f},
                {1.0f,0.53125f,0.0f},
                {1.0f,0.5f,0.0f},
                {1.0f,0.46875f,0.0f},
                {1.0f,0.4375f,0.0f},
                {1.0f,0.40625f,0.0f},
                {1.0f,0.375f,0.0f},
                {1.0f,0.34375f,0.0f},
                {1.0f,0.3125f,0.0f},
                {1.0f,0.28125f,0.0f},
                {1.0f,0.25f,0.0f},
                {1.0f,0.21875f,0.0f},
                {1.0f,0.1875f,0.0f},
                {1.0f,0.15625f,0.0f},
                {1.0f,0.125f,0.0f},
                {1.0f,0.09375f,0.0f},
                {1.0f,0.0625f,0.0f},
                {1.0f,0.03125f,0.0f},
                {1.0f,0.0f,0.0f},
                {0.96875f,0.0f,0.0f},
                {0.9375f,0.0f,0.0f},
                {0.90625f,0.0f,0.0f},
                {0.875f,0.0f,0.0f},
                {0.84375f,0.0f,0.0f},
                {0.8125f,0.0f,0.0f},
                {0.78125f,0.0f,0.0f},
                {0.75f,0.0f,0.0f},
                {0.71875f,0.0f,0.0f},
                {0.6875f,0.0f,0.0f},
                {0.65625f,0.0f,0.0f},
                {0.625f,0.0f,0.0f},
                {0.59375f,0.0f,0.0f},
                {0.5625f,0.0f,0.0f},
                {0.53125f,0.0f,0.0f},
                {0.5f,0.0f,0.0f}
};

1320 1321 1322 1323
#ifdef QGC_LIBFREENECT_ENABLED
void
Pixhawk3DWidget::updateRGBD(void)
{
1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345
    QSharedPointer<QByteArray> rgb = freenect->getRgbData();
    if (!rgb.isNull())
    {
        rgbImage->setImage(640, 480, 1,
                           GL_RGB, GL_RGB, GL_UNSIGNED_BYTE,
                           reinterpret_cast<unsigned char *>(rgb->data()),
                           osg::Image::NO_DELETE);
        rgbImage->dirty();
    }

    QSharedPointer<QByteArray> coloredDepth = freenect->getColoredDepthData();
    if (!coloredDepth.isNull())
    {
        depthImage->setImage(640, 480, 1,
                             GL_RGB, GL_RGB, GL_UNSIGNED_BYTE,
                             reinterpret_cast<unsigned char *>(coloredDepth->data()),
                             osg::Image::NO_DELETE);
        depthImage->dirty();
    }

    QSharedPointer< QVector<Freenect::Vector6D> > pointCloud =
            freenect->get6DPointCloudData();
1346 1347 1348 1349 1350

    osg::Geometry* geometry = rgbd3DNode->getDrawable(0)->asGeometry();

    osg::Vec3Array* vertices = static_cast<osg::Vec3Array*>(geometry->getVertexArray());
    osg::Vec4Array* colors = static_cast<osg::Vec4Array*>(geometry->getColorArray());
1351
    for (int i = 0; i < pointCloud->size(); ++i)
1352
    {
1353 1354 1355
        double x = pointCloud->at(i).x;
        double y = pointCloud->at(i).y;
        double z = pointCloud->at(i).z;
1356 1357
        (*vertices)[i].set(x, z, -y);

1358 1359
        if (enableRGBDColor)
        {
1360 1361 1362
            (*colors)[i].set(pointCloud->at(i).r / 255.0f,
                             pointCloud->at(i).g / 255.0f,
                             pointCloud->at(i).b / 255.0f,
1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373
                             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));
            (*colors)[i].set(colormap_jet[colorIndex][0],
                             colormap_jet[colorIndex][1],
                             colormap_jet[colorIndex][2],
                             1.0f);
        }
1374 1375 1376 1377 1378
    }

    if (geometry->getNumPrimitiveSets() == 0)
    {
        geometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POINTS,
1379
                                                      0, pointCloud->size()));
1380 1381 1382 1383
    }
    else
    {
        osg::DrawArrays* drawarrays = static_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));
1384
        drawarrays->setCount(pointCloud->size());
1385
    }
1386 1387
}
#endif
1388

1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403
int
Pixhawk3DWidget::findWaypoint(int mouseX, int mouseY)
{
    if (getSceneData() != NULL)
    {
        osgUtil::LineSegmentIntersector::Intersections intersections;

        if (computeIntersections(mouseX, height() - mouseY, intersections))
        {
            for (osgUtil::LineSegmentIntersector::Intersections::iterator
                 it = intersections.begin(); it != intersections.end(); it++)
            {
                for (uint i = 0 ; i < it->nodePath.size(); ++i)
                {
                    std::string nodeName = it->nodePath[i]->getName();
1404
                    if (nodeName.substr(0, 2).compare("wp") == 0)
1405
                    {
1406
                        return atoi(nodeName.substr(2).c_str());
1407 1408 1409 1410 1411 1412 1413 1414 1415
                    }
                }
            }
        }
    }

    return -1;
}

1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442
bool
Pixhawk3DWidget::findTarget(int mouseX, int mouseY)
{
    if (getSceneData() != NULL)
    {
        osgUtil::LineSegmentIntersector::Intersections intersections;

        if (computeIntersections(mouseX, height() - mouseY, intersections))
        {
            for (osgUtil::LineSegmentIntersector::Intersections::iterator
                 it = intersections.begin(); it != intersections.end(); it++)
            {
                for (uint i = 0 ; i < it->nodePath.size(); ++i)
                {
                    std::string nodeName = it->nodePath[i]->getName();
                    if (nodeName.compare("Target") == 0)
                    {
                        return true;
                    }
                }
            }
        }
    }

    return false;
}

1443 1444 1445 1446 1447 1448
void
Pixhawk3DWidget::showInsertWaypointMenu(const QPoint &cursorPos)
{
    QMenu menu;
    menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
1449
    menu.addAction("Select target", this, SLOT(selectTarget()));
1450 1451 1452 1453 1454 1455 1456 1457 1458
    menu.exec(cursorPos);
}

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

    QString text;
1459
    text = QString("Move waypoint %1").arg(QString::number(selectedWpIndex));
1460 1461
    menu.addAction(text, this, SLOT(moveWaypoint()));

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

1465
    text = QString("Delete waypoint %1").arg(QString::number(selectedWpIndex));
1466 1467 1468 1469 1470
    menu.addAction(text, this, SLOT(deleteWaypoint()));

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