Pixhawk3DWidget.cc 41.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 44 45 46 47 48 49
#include <osg/LineWidth>
#include <osg/ShapeDrawable>

#include "PixhawkCheetahGeode.h"
#include "UASManager.h"
#include "UASInterface.h"
#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 56
     , displayTarget(false)
     , displayWaypoints(true)
57 58
     , displayRGBD2D(false)
     , displayRGBD3D(false)
59
     , enableRGBDColor(true)
60
     , followCamera(true)
61
     , enableFreenect(false)
62 63 64
     , lastRobotX(0.0f)
     , lastRobotY(0.0f)
     , lastRobotZ(0.0f)
65
{
66
    setCameraParams(2.0f, 30.0f, 0.01f, 10000.0f);
67 68 69
    init(15.0f);

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

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

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

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

85
    // generate target model
86
    allocentricMap->addChild(createTarget());
87 88 89 90 91

    // generate waypoint model
    waypointsNode = createWaypoints();
    rollingMap->addChild(waypointsNode);

92 93
#ifdef QGC_LIBFREENECT_ENABLED
    freenect.reset(new Freenect());
94
    enableFreenect = freenect->init();
95 96
#endif

97
    // generate RGBD model
98 99 100 101 102
    if (enableFreenect)
    {
        rgbd3DNode = createRGBD3D();
        egocentricMap->addChild(rgbd3DNode);
    }
103

104 105
    setupHUD();

106 107 108
    // find available vehicle models in models folder
    vehicleModels = findVehicleModels();

109 110 111 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 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154
    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;
}

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)
        {
155
            trail.clear();
156 157 158 159 160 161 162 163 164 165
        }

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

166 167 168 169 170 171 172 173 174 175 176 177 178
void
Pixhawk3DWidget::showWaypoints(int state)
{
    if (state == Qt::Checked)
    {
        displayWaypoints = true;
    }
    else
    {
        displayWaypoints = false;
    }
}

179 180 181 182
void
Pixhawk3DWidget::selectMapSource(int index)
{
    mapNode->setImageryType(static_cast<Imagery::ImageryType>(index));
183 184 185 186 187 188 189 190 191

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

194 195 196
void
Pixhawk3DWidget::selectVehicleModel(int index)
{
197
    egocentricMap->removeChild(vehicleModel);
198
    vehicleModel = vehicleModels.at(index);
199
    egocentricMap->addChild(vehicleModel);
200 201
}

202
void
203
Pixhawk3DWidget::recenter(void)
204
{
205
    double robotX = 0.0f, robotY = 0.0f, robotZ = 0.0f;
206 207
    if (uas != NULL)
    {
208 209 210 211 212 213 214
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
        double altitude = uas->getAltitude();

        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
        robotZ = -altitude;
215 216
    }

217
    recenterCamera(robotY, robotX, -robotZ);
218 219 220
}

void
221
Pixhawk3DWidget::toggleFollowCamera(int32_t state)
222 223 224
{
    if (state == Qt::Checked)
    {
225
        followCamera = true;
226 227 228
    }
    else
    {
229
        followCamera = false;
230 231
    }
}
232

233 234 235 236 237
void
Pixhawk3DWidget::insertWaypoint(void)
{
    if (uas)
    {
238 239
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
240
        double altitude = uas->getAltitude();
241 242 243
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(uas->getLatitude(), uas->getLongitude(), x, y, utmZone);
244 245 246 247

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

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

251
        Waypoint* wp = new Waypoint(0,
252 253 254
                                    longitude,
                                    latitude,
                                    altitude);
255 256 257 258 259 260 261 262 263 264 265 266 267 268 269
        uas->getWaypointManager().addWaypoint(wp);
    }
}

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

void
Pixhawk3DWidget::setWaypoint(void)
{
    if (uas)
    {
270 271
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();
272
        double altitude = uas->getAltitude();
273 274 275
        double x, y;
        QString utmZone;
        Imagery::LLtoUTM(uas->getLatitude(), uas->getLongitude(), x, y, utmZone);
276 277 278 279

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

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

283 284 285
        const QVector<Waypoint *> waypoints =
                uas->getWaypointManager().getWaypointList();
        Waypoint* waypoint = waypoints.at(selectedWpIndex);
286 287 288
        waypoint->setX(longitude);
        waypoint->setY(latitude);
        waypoint->setZ(altitude);
289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305
    }
}

void
Pixhawk3DWidget::deleteWaypoint(void)
{
    if (uas)
    {
        uas->getWaypointManager().removeWaypoint(selectedWpIndex);
    }
}

void
Pixhawk3DWidget::setWaypointAltitude(void)
{
    if (uas)
    {
306
        bool ok;
307 308
        const QVector<Waypoint *> waypoints =
                uas->getWaypointManager().getWaypointList();
309 310 311 312
        Waypoint* waypoint = waypoints.at(selectedWpIndex);

        double newAltitude =
                QInputDialog::getDouble(this, tr("Set altitude of waypoint %1").arg(selectedWpIndex),
313
                                        tr("Altitude (m):"), waypoint->getZ(), -1000.0, 1000.0, 1, &ok);
314 315
        if (ok)
        {
316
            waypoint->setZ(newAltitude);
317
        }
318 319 320 321 322 323 324 325 326 327 328 329 330
    }
}

void
Pixhawk3DWidget::clearAllWaypoints(void)
{
    if (uas)
    {
        double altitude = uas->getAltitude();

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

331 332 333 334 335 336
        const QVector<Waypoint *> waypoints =
                uas->getWaypointManager().getWaypointList();
        for (int i = waypoints.size() - 1; i >= 0; --i)
        {
            uas->getWaypointManager().removeWaypoint(i);
        }
337 338 339
    }
}

340 341 342 343
QVector< osg::ref_ptr<osg::Node> >
Pixhawk3DWidget::findVehicleModels(void)
{
    QDir directory("models");
lm's avatar
lm committed
344
    QStringList files = directory.entryList(QStringList("*.osg"), QDir::Files);
345 346 347 348

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

    // add Pixhawk Bravo model
349
    nodes.push_back(PixhawkCheetahGeode::instance());
350

351
    // add all other models in folder
352 353 354 355 356
    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
357 358
        if (node)
        {
359
            nodes.push_back(node);
lm's avatar
lm committed
360 361 362
        }
        else
        {
363
            printf("%s\n", QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
lm's avatar
lm committed
364
        }
365 366
    }

lm's avatar
lm committed
367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388
//    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());
//        }
//    }

389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406
    return nodes;
}

void
Pixhawk3DWidget::buildLayout(void)
{
    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);

407 408 409 410 411 412
    QLabel* mapLabel = new QLabel("Map", this);
    QComboBox* mapComboBox = new QComboBox(this);
    mapComboBox->addItem("None");
    mapComboBox->addItem("Map (Google)");
    mapComboBox->addItem("Satellite (Google)");

413
    QLabel* modelLabel = new QLabel("Vehicle", this);
414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432
    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);
    layout->addWidget(gridCheckBox, 1, 0);
    layout->addWidget(trailCheckBox, 1, 1);
    layout->addWidget(waypointsCheckBox, 1, 2);
433
    layout->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 3);
434 435 436 437
    layout->addWidget(mapLabel, 1, 4);
    layout->addWidget(mapComboBox, 1, 5);
    layout->addWidget(modelLabel, 1, 6);
    layout->addWidget(modelComboBox, 1, 7);
438 439 440
    layout->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 8);
    layout->addWidget(recenterButton, 1, 9);
    layout->addWidget(followCameraCheckBox, 1, 10);
441 442 443 444 445 446 447 448 449 450
    layout->setRowStretch(0, 100);
    layout->setRowStretch(1, 1);
    setLayout(layout);

    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)));
451 452
    connect(mapComboBox, SIGNAL(currentIndexChanged(int)),
            this, SLOT(selectMapSource(int)));
453 454 455 456 457 458
    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)));
}
459

460 461 462
void
Pixhawk3DWidget::display(void)
{
463
    if (uas == NULL)
464
    {
465 466 467
        return;
    }

468 469 470 471 472 473 474 475 476 477
    double latitude = uas->getLatitude();
    double longitude = uas->getLongitude();
    double altitude = uas->getAltitude();

    double robotX;
    double robotY;
    QString utmZone;
    Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
    double robotZ = -altitude;

478 479 480
    double robotRoll = uas->getRoll();
    double robotPitch = uas->getPitch();
    double robotYaw = uas->getYaw();
481 482 483 484 485 486 487 488 489 490

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

        recenterCamera(robotY, robotX, -robotZ);

        return;
491 492
    }

493 494
    if (followCamera)
    {
495 496 497
        double dx = robotY - lastRobotY;
        double dy = robotX - lastRobotX;
        double dz = lastRobotZ - robotZ;
498 499

        moveCamera(dx, dy, dz);
500 501
    }

502 503 504 505
    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)));
506

507 508 509 510 511 512 513
    if (displayTrail)
    {
        updateTrail(robotX, robotY, robotZ);
    }

    if (displayImagery)
    {
514
        updateImagery(robotX, robotY, robotZ, utmZone);
515 516 517 518 519 520 521 522 523 524 525 526
    }

    if (displayTarget)
    {
        updateTarget();
    }

    if (displayWaypoints)
    {
        updateWaypoints();
    }

527
#ifdef QGC_LIBFREENECT_ENABLED
528
    if (enableFreenect && (displayRGBD2D || displayRGBD3D))
529 530 531
    {
        updateRGBD();
    }
532 533
#endif
    updateHUD(robotX, robotY, robotZ, robotRoll, robotPitch, robotYaw);
534 535

    // set node visibility
536

537 538
    rollingMap->setChildValue(gridNode, displayGrid);
    rollingMap->setChildValue(trailNode, displayTrail);
539
    rollingMap->setChildValue(mapNode, displayImagery);
540 541
    rollingMap->setChildValue(targetNode, displayTarget);
    rollingMap->setChildValue(waypointsNode, displayWaypoints);
542 543 544 545
    if (enableFreenect)
    {
        egocentricMap->setChildValue(rgbd3DNode, displayRGBD3D);
    }
546 547
    hudGroup->setChildValue(rgb2DGeode, displayRGBD2D);
    hudGroup->setChildValue(depth2DGeode, displayRGBD2D);
548 549 550 551

    lastRobotX = robotX;
    lastRobotY = robotY;
    lastRobotZ = robotZ;
552 553
}

554 555 556 557 558 559 560 561 562 563
void
Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
{
    if (!event->text().isEmpty())
    {
        switch (*(event->text().toAscii().data()))
        {
        case '1':
            displayRGBD2D = !displayRGBD2D;
            break;
564 565 566
        case '2':
            displayRGBD3D = !displayRGBD3D;
            break;
567 568 569
        case 'c': case 'C':
            enableRGBDColor = !enableRGBDColor;
            break;
570 571 572 573 574 575
        }
    }

    Q3DWidget::keyPressEvent(event);
}

576 577 578
void
Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
{
579
    if (event->button() == Qt::LeftButton)
580
    {
581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602
        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;
        }
603 604 605 606 607
    }

    Q3DWidget::mousePressEvent(event);
}

608 609 610 611
osg::ref_ptr<osg::Geode>
Pixhawk3DWidget::createGrid(void)
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
612 613 614 615
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
616 617 618 619

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

620 621
    osg::ref_ptr<osg::Vec3Array> fineCoords(new osg::Vec3Array);
    osg::ref_ptr<osg::Vec3Array> coarseCoords(new osg::Vec3Array);
622 623 624 625

    // draw a 20m x 20m grid with 0.25m resolution
    for (float i = -radius; i <= radius; i += resolution)
    {
pixhawk's avatar
pixhawk committed
626
        if (fabsf(i - floor(i + 0.5f)) < 0.01f)
627 628 629 630 631 632 633 634 635 636 637 638 639
        {
            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));
        }
640 641
    }

642 643
    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);
644 645 646

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669
    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);
670 671 672 673 674 675 676 677 678 679 680 681

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

682
    trailVertices = new osg::Vec3dArray;
683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702
    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;
}

703
osg::ref_ptr<Imagery>
704 705
Pixhawk3DWidget::createMap(void)
{
706
    return osg::ref_ptr<Imagery>(new Imagery());
707 708
}

709
osg::ref_ptr<osg::Node>
710 711
Pixhawk3DWidget::createTarget(void)
{
712
    targetPosition = new osg::PositionAttitudeTransform;
713

714 715 716 717
    targetNode = new osg::Geode;
    targetPosition->addChild(targetNode);

    return targetPosition;
718 719 720 721 722
}

osg::ref_ptr<osg::Group>
Pixhawk3DWidget::createWaypoints(void)
{
723
    osg::ref_ptr<osg::Group> group(new osg::Group());
724

725
    return group;
726 727
}

728
osg::ref_ptr<osg::Geode>
729
Pixhawk3DWidget::createRGBD3D(void)
730
{
731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746
    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;
747 748
}

749 750 751 752 753 754 755
void
Pixhawk3DWidget::setupHUD(void)
{
    osg::ref_ptr<osg::Vec4Array> hudColors(new osg::Vec4Array);
    hudColors->push_back(osg::Vec4(0.0f, 0.0f, 0.0f, 0.2f));

    hudBackgroundGeometry = new osg::Geometry;
756 757 758 759
    hudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                                               0, 4));
    hudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                                               4, 4));
760 761
    hudBackgroundGeometry->setColorArray(hudColors);
    hudBackgroundGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);
762
    hudBackgroundGeometry->setUseDisplayList(false);
763 764 765 766 767 768 769

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

770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787
    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);
788 789 790 791

    scaleGeode = new HUDScaleGeode;
    scaleGeode->init();
    hudGroup->addChild(scaleGeode);
792 793 794
}

void
795
Pixhawk3DWidget::resizeHUD(void)
796
{
797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816
    int topHUDHeight = 30;
    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);
817 818 819

    statusText->setPosition(osg::Vec3(10, height() - 20, -1.5));

820 821 822 823 824 825 826 827 828 829 830 831
    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
832 833
Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ,
                           double robotRoll, double robotPitch, double robotYaw)
834 835 836
{
    resizeHUD();

837 838
    std::pair<double,double> cursorPosition =
            getGlobalCursorPosition(getMouseX(), getMouseY(), -robotZ);
839 840 841 842 843 844 845 846 847 848 849 850 851

    std::ostringstream oss;
    oss.setf(std::ios::fixed, std::ios::floatfield);
    oss.precision(2);
    oss << " x = " << robotX <<
            " y = " << robotY <<
            " z = " << robotZ <<
            " r = " << robotRoll <<
            " p = " << robotPitch <<
            " y = " << robotYaw <<
            " Cursor [" << cursorPosition.first <<
            " " << cursorPosition.second << "]";
    statusText->setText(oss.str());
852

853 854 855 856 857 858 859 860 861
    bool darkBackground = true;
    if (mapNode->getImageryType() == Imagery::GOOGLE_MAP)
    {
        darkBackground = false;
    }

    scaleGeode->update(height(), cameraParams.cameraFov,
                       cameraManipulator->getDistance(), darkBackground);

862 863 864 865 866 867 868 869
    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();

870 871 872 873
        depthImage->setImage(640, 480, 1,
                             GL_RGB, GL_RGB, GL_UNSIGNED_BYTE,
                             reinterpret_cast<unsigned char *>(coloredDepth->data()),
                             osg::Image::NO_DELETE);
874 875
        depthImage->dirty();
    }
876 877 878
}

void
879
Pixhawk3DWidget::updateTrail(double robotX, double robotY, double robotZ)
880 881 882 883 884 885 886 887 888
{
    if (robotX == 0.0f || robotY == 0.0f || robotZ == 0.0f)
    {
        return;
    }

    bool addToTrail = false;
    if (trail.size() > 0)
    {
889 890 891
        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)
892 893 894 895 896 897 898 899 900 901 902
        {
            addToTrail = true;
        }
    }
    else
    {
        addToTrail = true;
    }

    if (addToTrail)
    {
903
        osg::Vec3d p(robotX, robotY, robotZ);
904 905 906
        if (trail.size() == trail.capacity())
        {
            memcpy(trail.data(), trail.data() + 1,
907
                   (trail.size() - 1) * sizeof(osg::Vec3d));
908 909 910 911 912 913 914 915 916 917 918
            trail[trail.size() - 1] = p;
        }
        else
        {
            trail.append(p);
        }
    }

    trailVertices->clear();
    for (int i = 0; i < trail.size(); ++i)
    {
919 920 921
        trailVertices->push_back(osg::Vec3d(trail[i].y() - robotY,
                                            trail[i].x() - robotX,
                                            -(trail[i].z() - robotZ)));
922 923 924 925 926 927 928
    }

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

929
void
930
Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
931
                               const QString& zone)
932
{
933 934 935 936 937
    if (mapNode->getImageryType() == Imagery::BLANK_MAP)
    {
        return;
    }

938 939 940 941 942 943 944
    double viewingRadius = cameraManipulator->getDistance() * 10.0;
    if (viewingRadius < 100.0)
    {
        viewingRadius = 100.0;
    }

    double minResolution = 0.25;
945
    double centerResolution = cameraManipulator->getDistance() / 50.0;
946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977
    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(),
978 979
                    originX,
                    originY,
980
                    originZ,
981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003
                    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();
}

1004
void
1005
Pixhawk3DWidget::updateTarget(void)
1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018
{
    static double radius = 0.2;
    static bool expand = true;

    if (radius < 0.1)
    {
        expand = true;
    }
    else if (radius > 0.25)
    {
        expand = false;
    }

1019
    if (targetNode->getNumDrawables() > 0)
1020
    {
1021
        targetNode->removeDrawables(0, targetNode->getNumDrawables());
1022 1023
    }

1024 1025 1026 1027 1028 1029
    osg::ref_ptr<osg::ShapeDrawable> sd = new osg::ShapeDrawable;
    osg::ref_ptr<osg::Sphere> sphere = new osg::Sphere;
    sphere->setRadius(radius);
    sd->setShape(sphere);
    sd->setColor(osg::Vec4(0.0f, 0.7f, 1.0f, 1.0f));

1030
    targetNode->addDrawable(sd);
1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046

    if (expand)
    {
        radius += 0.02;
    }
    else
    {
        radius -= 0.02;
    }
}

void
Pixhawk3DWidget::updateWaypoints(void)
{
    if (uas)
    {
1047 1048 1049 1050 1051 1052
        double latitude = uas->getLatitude();
        double longitude = uas->getLongitude();

        double robotX, robotY;
        QString utmZone;
        Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
1053
        double robotZ = -uas->getAltitude();
1054

1055 1056 1057 1058 1059 1060 1061 1062 1063
        if (waypointsNode->getNumChildren() > 0)
        {
            waypointsNode->removeChild(0, waypointsNode->getNumChildren());
        }

        const QVector<Waypoint *>& list = uas->getWaypointManager().getWaypointList();

        for (int i = 0; i < list.size(); i++)
        {
1064 1065
            Waypoint* wp = list.at(i);

1066
            osg::ref_ptr<osg::ShapeDrawable> sd = new osg::ShapeDrawable;
1067
            osg::ref_ptr<osg::Cylinder> cylinder =
1068
                    new osg::Cylinder(osg::Vec3d(0.0, 0.0, wp->getZ() / 2.0),
1069 1070 1071 1072 1073
                                      wp->getOrbit(),
                                      fabs(wp->getZ()));

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

1075
            if (wp->getCurrent())
1076
            {
1077
                sd->setColor(osg::Vec4(1.0f, 0.3f, 0.3f, 0.5f));
1078 1079 1080
            }
            else
            {
1081
                sd->setColor(osg::Vec4(0.0f, 1.0f, 0.0f, 0.5f));
1082 1083 1084 1085 1086
            }

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

1087 1088 1089 1090
            char wpLabel[10];
            sprintf(wpLabel, "wp%d", i);
            geode->setName(wpLabel);

1091 1092 1093
            double wpX, wpY;
            Imagery::LLtoUTM(wp->getY(), wp->getX(), wpX, wpY, utmZone);

1094 1095
            if (i < list.size() - 1)
            {
1096 1097 1098 1099
                double nextWpX, nextWpY;
                Imagery::LLtoUTM(list.at(i+1)->getY(), list.at(i+1)->getX(),
                                 nextWpX, nextWpY, utmZone);

1100 1101
                osg::ref_ptr<osg::Geometry> geometry = new osg::Geometry;
                osg::ref_ptr<osg::Vec3dArray> vertices = new osg::Vec3dArray;
1102 1103 1104 1105
                vertices->push_back(osg::Vec3d(0.0, 0.0, wp->getZ()));
                vertices->push_back(osg::Vec3d(nextWpY - wpY,
                                               nextWpX - wpX,
                                               list.at(i+1)->getZ()));
1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117
                geometry->setVertexArray(vertices);

                osg::ref_ptr<osg::Vec4Array> colors = new osg::Vec4Array;
                colors->push_back(osg::Vec4(0.0f, 1.0f, 0.0f, 0.5f));
                geometry->setColorArray(colors);
                geometry->setColorBinding(osg::Geometry::BIND_OVERALL);

                geometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0, 2));

                osg::ref_ptr<osg::LineWidth> linewidth(new osg::LineWidth());
                linewidth->setWidth(2.0f);
                geometry->getOrCreateStateSet()->setAttributeAndModes(linewidth, osg::StateAttribute::ON);
1118
                geometry->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
1119 1120 1121 1122

                geode->addDrawable(geometry);
            }

1123 1124 1125
            osg::ref_ptr<osg::PositionAttitudeTransform> pat =
                    new osg::PositionAttitudeTransform;

1126 1127
            pat->setPosition(osg::Vec3d(wpY - robotY,
                                        wpX - robotX,
1128
                                        robotZ));
1129 1130 1131 1132 1133 1134

            waypointsNode->addChild(pat);
            pat->addChild(geode);
        }
    }
}
1135

1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 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 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
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}
};

1268 1269 1270 1271 1272
#ifdef QGC_LIBFREENECT_ENABLED
void
Pixhawk3DWidget::updateRGBD(void)
{
    rgb = freenect->getRgbData();
1273
    coloredDepth = freenect->getColoredDepthData();
1274
    pointCloud = freenect->get6DPointCloudData();
1275 1276 1277 1278 1279 1280 1281

    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());
    for (int i = 0; i < pointCloud.size(); ++i)
    {
1282 1283 1284
        double x = pointCloud[i].x;
        double y = pointCloud[i].y;
        double z = pointCloud[i].z;
1285 1286
        (*vertices)[i].set(x, z, -y);

1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302
        if (enableRGBDColor)
        {
            (*colors)[i].set(pointCloud[i].r / 255.0f,
                             pointCloud[i].g / 255.0f,
                             pointCloud[i].b / 255.0f,
                             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);
        }
1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314
    }

    if (geometry->getNumPrimitiveSets() == 0)
    {
        geometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POINTS,
                                                      0, pointCloud.size()));
    }
    else
    {
        osg::DrawArrays* drawarrays = static_cast<osg::DrawArrays*>(geometry->getPrimitiveSet(0));
        drawarrays->setCount(pointCloud.size());
    }
1315 1316
}
#endif
1317 1318 1319 1320

void
Pixhawk3DWidget::markTarget(void)
{
1321
    double robotZ = 0.0f;
1322 1323 1324 1325 1326
    if (uas != NULL)
    {
        robotZ = uas->getLocalZ();
    }

1327 1328 1329 1330 1331 1332
    std::pair<double,double> cursorWorldCoords =
            getGlobalCursorPosition(getMouseX(), getMouseY(), -robotZ);

    double targetX = cursorWorldCoords.first;
    double targetY = cursorWorldCoords.second;
    double targetZ = robotZ;
1333

1334
    targetPosition->setPosition(osg::Vec3d(targetY, targetX, -targetZ));
1335 1336 1337 1338 1339

    displayTarget = true;

    if (uas)
    {
1340
        uas->setTargetPosition(targetX, targetY, targetZ, 0.0f);
1341 1342 1343 1344
    }

    targetButton->setChecked(false);
}
1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360

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();
1361
                    if (nodeName.substr(0, 2).compare("wp") == 0)
1362
                    {
1363 1364
                        qDebug() << nodeName.c_str() << "Got!!";
                        return atoi(nodeName.substr(2).c_str());
1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388
                    }
                }
            }
        }
    }

    return -1;
}

void
Pixhawk3DWidget::showInsertWaypointMenu(const QPoint &cursorPos)
{
    QMenu menu;
    menu.addAction("Insert new waypoint", this, SLOT(insertWaypoint()));
    menu.addAction("Clear all waypoints", this, SLOT(clearAllWaypoints()));
    menu.exec(cursorPos);
}

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

    QString text;
1389
    text = QString("Move waypoint %1").arg(QString::number(selectedWpIndex));
1390 1391
    menu.addAction(text, this, SLOT(moveWaypoint()));

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

1395
    text = QString("Delete waypoint %1").arg(QString::number(selectedWpIndex));
1396 1397 1398 1399 1400
    menu.addAction(text, this, SLOT(deleteWaypoint()));

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