Pixhawk3DWidget.cc 30.1 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 50 51 52 53
#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)
     , displayGrid(true)
     , displayTrail(false)
     , displayTarget(false)
     , displayWaypoints(true)
54 55
     , displayRGBD2D(false)
     , displayRGBD3D(false)
56
     , followCamera(true)
57 58 59
     , lastRobotX(0.0f)
     , lastRobotY(0.0f)
     , lastRobotZ(0.0f)
60
{
61
    setCameraParams(2.0f, 30.0f, 0.01f, 10000.0f);
62 63 64
    init(15.0f);

    // generate Pixhawk Cheetah model
65 66
    vehicleModel = PixhawkCheetahGeode::instance();
    egocentricMap->addChild(vehicleModel);
67 68 69 70 71 72 73 74 75

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

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

76
#ifdef QGC_OSGEARTH_ENABLED
77 78 79
    // generate map model
    mapNode = createMap();
    root->addChild(mapNode);
80
#endif
81

82
    // generate target model
83
    allocentricMap->addChild(createTarget());
84 85 86 87 88

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

89 90 91 92 93
#ifdef QGC_LIBFREENECT_ENABLED
    freenect.reset(new Freenect());
    freenect->init();
#endif

94 95 96 97
    // generate RGBD model
    rgbd3DNode = createRGBD3D();
    egocentricMap->addChild(rgbd3DNode);

98 99
    setupHUD();

100 101 102
    // find available vehicle models in models folder
    vehicleModels = findVehicleModels();

103 104 105 106 107 108 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
    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)
        {
149
            trail.clear();
150 151 152 153 154 155 156 157 158 159
        }

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

160 161 162 163 164 165 166 167 168 169 170 171 172
void
Pixhawk3DWidget::showWaypoints(int state)
{
    if (state == Qt::Checked)
    {
        displayWaypoints = true;
    }
    else
    {
        displayWaypoints = false;
    }
}

173 174 175
void
Pixhawk3DWidget::selectVehicleModel(int index)
{
176
    egocentricMap->removeChild(vehicleModel);
177
    vehicleModel = vehicleModels.at(index);
178
    egocentricMap->addChild(vehicleModel);
179 180
}

181
void
182
Pixhawk3DWidget::recenter(void)
183
{
184 185 186 187 188 189 190 191
    float robotX = 0.0f, robotY = 0.0f, robotZ = 0.0f;
    if (uas != NULL)
    {
        robotX = uas->getLocalX();
        robotY = uas->getLocalY();
        robotZ = uas->getLocalZ();
    }

192
    recenterCamera(robotY, robotX, -robotZ);
193 194 195
}

void
196
Pixhawk3DWidget::toggleFollowCamera(int32_t state)
197 198 199
{
    if (state == Qt::Checked)
    {
200
        followCamera = true;
201 202 203
    }
    else
    {
204
        followCamera = false;
205 206
    }
}
207
#include <osgDB/WriteFile>
208 209 210 211
QVector< osg::ref_ptr<osg::Node> >
Pixhawk3DWidget::findVehicleModels(void)
{
    QDir directory("models");
lm's avatar
lm committed
212
    QStringList files = directory.entryList(QStringList("*.osg"), QDir::Files);
213 214 215 216

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

    // add Pixhawk Bravo model
217
    nodes.push_back(PixhawkCheetahGeode::instance());
218

219
    // add all other models in folder
220 221 222 223 224
    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
225 226
        if (node)
        {
227
            nodes.push_back(node);
lm's avatar
lm committed
228 229 230 231 232
        }
        else
        {
            printf(QString("ERROR: Could not load file " + directory.absoluteFilePath(files[i]) + "\n").toStdString().c_str());
        }
233 234
    }

lm's avatar
lm committed
235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256
//    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());
//        }
//    }

257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299
    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);

    QLabel* modelLabel = new QLabel("Vehicle Model", this);
    QComboBox* modelComboBox = new QComboBox(this);
    for (int i = 0; i < vehicleModels.size(); ++i)
    {
        modelComboBox->addItem(vehicleModels[i]->getName().c_str());
    }

    targetButton = new QPushButton(this);
    targetButton->setCheckable(true);
    targetButton->setChecked(false);
    targetButton->setIcon(QIcon(QString::fromUtf8(":/images/status/weather-clear.svg")));

    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);
300
    layout->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 3);
301 302 303
    layout->addWidget(modelLabel, 1, 4);
    layout->addWidget(modelComboBox, 1, 5);
    layout->addWidget(targetButton, 1, 6);
304
    layout->addItem(new QSpacerItem(10, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 7);
305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322
    layout->addWidget(recenterButton, 1, 8);
    layout->addWidget(followCameraCheckBox, 1, 9);
    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)));
    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)));
}
323

324 325 326
void
Pixhawk3DWidget::display(void)
{
327
    if (uas == NULL)
328
    {
329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347
        return;
    }

    float robotX = uas->getLocalX();
    float robotY = uas->getLocalY();
    float robotZ = uas->getLocalZ();
    float robotRoll = uas->getRoll();
    float robotPitch = uas->getPitch();
    float robotYaw = uas->getYaw();

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

        recenterCamera(robotY, robotX, -robotZ);

        return;
348 349
    }

350 351
    if (followCamera)
    {
352 353 354 355 356
        float dx = robotY - lastRobotY;
        float dy = robotX - lastRobotX;
        float dz = lastRobotZ - robotZ;

        moveCamera(dx, dy, dz);
357 358
    }

359 360 361 362 363 364
    robotPosition->setPosition(osg::Vec3(robotY, robotX, -robotZ));
    robotAttitude->setAttitude(osg::Quat(-robotYaw, osg::Vec3f(0.0f, 0.0f, 1.0f),
                                         robotPitch, osg::Vec3f(1.0f, 0.0f, 0.0f),
                                         robotRoll, osg::Vec3f(0.0f, 1.0f, 0.0f)));

    updateTrail(robotX, robotY, robotZ);
365
    updateTarget();
366
    updateWaypoints();
367 368 369 370
#ifdef QGC_LIBFREENECT_ENABLED
    updateRGBD();
#endif
    updateHUD(robotX, robotY, robotZ, robotRoll, robotPitch, robotYaw);
371 372 373 374 375 376

    // set node visibility
    rollingMap->setChildValue(gridNode, displayGrid);
    rollingMap->setChildValue(trailNode, displayTrail);
    rollingMap->setChildValue(targetNode, displayTarget);
    rollingMap->setChildValue(waypointsNode, displayWaypoints);
377
    egocentricMap->setChildValue(rgbd3DNode, displayRGBD3D);
378 379
    hudGroup->setChildValue(rgb2DGeode, displayRGBD2D);
    hudGroup->setChildValue(depth2DGeode, displayRGBD2D);
380 381 382 383

    lastRobotX = robotX;
    lastRobotY = robotY;
    lastRobotZ = robotZ;
384 385
}

386 387 388 389 390 391 392 393 394 395
void
Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
{
    if (!event->text().isEmpty())
    {
        switch (*(event->text().toAscii().data()))
        {
        case '1':
            displayRGBD2D = !displayRGBD2D;
            break;
396 397 398
        case '2':
            displayRGBD3D = !displayRGBD3D;
            break;
399 400 401 402 403 404
        }
    }

    Q3DWidget::keyPressEvent(event);
}

405 406 407 408 409 410 411 412 413 414 415
void
Pixhawk3DWidget::mousePressEvent(QMouseEvent* event)
{
    if (event->button() == Qt::LeftButton && targetButton->isChecked())
    {
        markTarget();
    }

    Q3DWidget::mousePressEvent(event);
}

416 417 418 419
osg::ref_ptr<osg::Geode>
Pixhawk3DWidget::createGrid(void)
{
    osg::ref_ptr<osg::Geode> geode(new osg::Geode());
420 421 422 423
    osg::ref_ptr<osg::Geometry> fineGeometry(new osg::Geometry());
    osg::ref_ptr<osg::Geometry> coarseGeometry(new osg::Geometry());
    geode->addDrawable(fineGeometry);
    geode->addDrawable(coarseGeometry);
424 425 426 427

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

428 429
    osg::ref_ptr<osg::Vec3Array> fineCoords(new osg::Vec3Array);
    osg::ref_ptr<osg::Vec3Array> coarseCoords(new osg::Vec3Array);
430 431 432 433

    // draw a 20m x 20m grid with 0.25m resolution
    for (float i = -radius; i <= radius; i += resolution)
    {
434 435 436 437 438 439 440 441 442 443 444 445 446 447
        if (fabsf(i - roundf(i)) < 0.01f)
        {
            coarseCoords->push_back(osg::Vec3(i, -radius, 0.0f));
            coarseCoords->push_back(osg::Vec3(i, radius, 0.0f));
            coarseCoords->push_back(osg::Vec3(-radius, i, 0.0f));
            coarseCoords->push_back(osg::Vec3(radius, i, 0.0f));
        }
        else
        {
            fineCoords->push_back(osg::Vec3(i, -radius, 0.0f));
            fineCoords->push_back(osg::Vec3(i, radius, 0.0f));
            fineCoords->push_back(osg::Vec3(-radius, i, 0.0f));
            fineCoords->push_back(osg::Vec3(radius, i, 0.0f));
        }
448 449
    }

450 451
    fineGeometry->setVertexArray(fineCoords);
    coarseGeometry->setVertexArray(coarseCoords);
452 453 454

    osg::ref_ptr<osg::Vec4Array> color(new osg::Vec4Array);
    color->push_back(osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f));
455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477
    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);
478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510

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

    trailVertices = new osg::Vec3Array;
    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;
}

511
#ifdef QGC_OSGEARTH_ENABLED
512 513 514 515 516 517 518 519
osg::ref_ptr<osgEarth::MapNode>
Pixhawk3DWidget::createMap(void)
{
    osg::ref_ptr<osg::Node> model = osgDB::readNodeFile("map.earth");
    osg::ref_ptr<osgEarth::MapNode> node = osgEarth::MapNode::findMapNode(model);

    return node;
}
520
#endif
521

522
osg::ref_ptr<osg::Node>
523 524
Pixhawk3DWidget::createTarget(void)
{
525
    targetPosition = new osg::PositionAttitudeTransform;
526

527 528 529 530
    targetNode = new osg::Geode;
    targetPosition->addChild(targetNode);

    return targetPosition;
531 532 533 534 535
}

osg::ref_ptr<osg::Group>
Pixhawk3DWidget::createWaypoints(void)
{
536
    osg::ref_ptr<osg::Group> group(new osg::Group());
537

538
    return group;
539 540
}

541
osg::ref_ptr<osg::Geode>
542
Pixhawk3DWidget::createRGBD3D(void)
543
{
544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559
    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;
560 561
}

562 563 564 565 566 567 568
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;
569 570 571 572
    hudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                                               0, 4));
    hudBackgroundGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POLYGON,
                                                               4, 4));
573 574
    hudBackgroundGeometry->setColorArray(hudColors);
    hudBackgroundGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);
575
    hudBackgroundGeometry->setUseDisplayList(false);
576 577 578 579 580 581 582

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

583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600
    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);
601 602 603
}

void
604
Pixhawk3DWidget::resizeHUD(void)
605
{
606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625
    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);
626 627 628

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

629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645
    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
Pixhawk3DWidget::updateHUD(float robotX, float robotY, float robotZ,
                           float robotRoll, float robotPitch, float robotYaw)
{
    resizeHUD();

646 647
    std::pair<double,double> cursorPosition =
            getGlobalCursorPosition(getMouseX(), getMouseY(), -robotZ);
648 649 650 651 652 653 654 655 656 657 658 659 660

    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());
661 662 663 664 665 666 667 668 669

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

670 671 672 673
        depthImage->setImage(640, 480, 1,
                             GL_RGB, GL_RGB, GL_UNSIGNED_BYTE,
                             reinterpret_cast<unsigned char *>(coloredDepth->data()),
                             osg::Image::NO_DELETE);
674 675
        depthImage->dirty();
    }
676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 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
}

void
Pixhawk3DWidget::updateTrail(float robotX, float robotY, float robotZ)
{
    if (robotX == 0.0f || robotY == 0.0f || robotZ == 0.0f)
    {
        return;
    }

    bool addToTrail = false;
    if (trail.size() > 0)
    {
        if (fabsf(robotX - trail[trail.size() - 1].x()) > 0.01f ||
            fabsf(robotY - trail[trail.size() - 1].y()) > 0.01f ||
            fabsf(robotZ - trail[trail.size() - 1].z()) > 0.01f)
        {
            addToTrail = true;
        }
    }
    else
    {
        addToTrail = true;
    }

    if (addToTrail)
    {
        osg::Vec3 p(robotX, robotY, robotZ);
        if (trail.size() == trail.capacity())
        {
            memcpy(trail.data(), trail.data() + 1,
                   (trail.size() - 1) * sizeof(osg::Vec3));
            trail[trail.size() - 1] = p;
        }
        else
        {
            trail.append(p);
        }
    }

    trailVertices->clear();
    for (int i = 0; i < trail.size(); ++i)
    {
        trailVertices->push_back(osg::Vec3(trail[i].y() - robotY,
                                           trail[i].x() - robotX,
                                           -(trail[i].z() - robotZ)));
    }

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

void
730
Pixhawk3DWidget::updateTarget(void)
731 732 733 734 735 736 737 738 739 740 741 742 743
{
    static double radius = 0.2;
    static bool expand = true;

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

744
    if (targetNode->getNumDrawables() > 0)
745
    {
746
        targetNode->removeDrawables(0, targetNode->getNumDrawables());
747 748
    }

749 750 751 752 753 754
    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));

755
    targetNode->addDrawable(sd);
756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809

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

void
Pixhawk3DWidget::updateWaypoints(void)
{
    if (uas)
    {
        if (waypointsNode->getNumChildren() > 0)
        {
            waypointsNode->removeChild(0, waypointsNode->getNumChildren());
        }

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

        for (int i = 0; i < list.size(); i++)
        {
            osg::ref_ptr<osg::ShapeDrawable> sd = new osg::ShapeDrawable;
            osg::ref_ptr<osg::Sphere> sphere = new osg::Sphere;
            sphere->setRadius(0.2);
            sd->setShape(sphere);

            if (list.at(i)->getCurrent())
            {
                sd->setColor(osg::Vec4(1.0f, 0.3f, 0.3f, 1.0f));
            }
            else
            {
                sd->setColor(osg::Vec4(0.0f, 1.0f, 1.0f, 1.0f));
            }

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

            osg::ref_ptr<osg::PositionAttitudeTransform> pat =
                    new osg::PositionAttitudeTransform;

            pat->setPosition(osg::Vec3d(list.at(i)->getY() - uas->getLocalY(),
                                        list.at(i)->getX() - uas->getLocalX(),
                                        0.0));

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

811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942
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}
};

943 944 945 946 947
#ifdef QGC_LIBFREENECT_ENABLED
void
Pixhawk3DWidget::updateRGBD(void)
{
    rgb = freenect->getRgbData();
948
    coloredDepth = freenect->getColoredDepthData();
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 978 979
    pointCloud = freenect->getPointCloudData();

    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)
    {
        double x = pointCloud[i].x();
        double y = pointCloud[i].y();
        double z = pointCloud[i].z();
        (*vertices)[i].set(x, z, -y);

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

    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());
    }
980 981
}
#endif
982 983 984 985 986 987 988 989 990 991

void
Pixhawk3DWidget::markTarget(void)
{
    float robotZ = 0.0f;
    if (uas != NULL)
    {
        robotZ = uas->getLocalZ();
    }

992 993 994 995 996 997
    std::pair<double,double> cursorWorldCoords =
            getGlobalCursorPosition(getMouseX(), getMouseY(), -robotZ);

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

999
    targetPosition->setPosition(osg::Vec3d(targetY, targetX, -targetZ));
1000 1001 1002 1003 1004

    displayTarget = true;

    if (uas)
    {
1005
        uas->setTargetPosition(targetX, targetY, targetZ, 0.0f);
1006 1007 1008 1009
    }

    targetButton->setChecked(false);
}