QMap3DWidget.cc 19.7 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
/*=====================================================================

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 QMap3DWidget.
 *
 *   @author Lionel Heng <hengli@student.ethz.ch>
 *
 */

lm's avatar
lm committed
32 33
#include "QMap3DWidget.h"

34
#include <QCheckBox>
lm's avatar
lm committed
35 36
#include <sys/time.h>

pixhawk's avatar
pixhawk committed
37
//#include "QGCGlut.h"
38
#include "CheetahModel.h"
lm's avatar
lm committed
39 40
#include "UASManager.h"
#include "UASInterface.h"
lm's avatar
lm committed
41
#include "QGC.h"
lm's avatar
lm committed
42 43

QMap3DWidget::QMap3DWidget(QWidget* parent)
44 45 46
     : Q3DWidget(parent)
     , uas(NULL)
     , lastRedrawTime(0.0)
47
     , displayGrid(true)
48
     , displayImagery(false)
49
     , displayTrail(false)
50 51 52
     , lockCamera(true)
     , updateLastUnlockedPose(true)
     , displayTarget(false)
lm's avatar
lm committed
53
     , displayWaypoints(true)
54
     , imagery(0)
lm's avatar
lm committed
55 56 57
{
    setFocusPolicy(Qt::StrongFocus);

58
    initialize(10, 10, 1000, 900, 15.0f);
59
    setCameraParams(0.05f, 0.5f, 0.01f, 0.5f, 30.0f, 0.01f, 1000000.0f);
lm's avatar
lm committed
60 61

    setDisplayFunc(display, this);
62
    setMouseFunc(mouse, this);
lm's avatar
lm committed
63 64
    addTimerFunc(100, timer, this);

65
    buildLayout();
lm's avatar
lm committed
66 67 68 69 70 71 72 73 74 75

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

QMap3DWidget::~QMap3DWidget()
{

}

76
void
77
QMap3DWidget::buildLayout(void)
78
{
79 80 81 82 83 84 85 86
    QCheckBox* gridCheckBox = new QCheckBox(this);
    gridCheckBox->setText("Grid");
    gridCheckBox->setChecked(displayGrid);

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

lm's avatar
lm committed
87 88 89 90
    QCheckBox* waypointsCheckBox = new QCheckBox(this);
    waypointsCheckBox->setText("Waypoints");
    waypointsCheckBox->setChecked(displayWaypoints);

91 92 93
    QLabel* imageryLabel = new QLabel(this);
    imageryLabel->setText("Imagery");

94
    imageryComboBox = new QComboBox(this);
95 96 97 98
    imageryComboBox->addItem("None");
    imageryComboBox->addItem("Map (Google)");
    imageryComboBox->addItem("Satellite (Google)");

99 100 101 102 103 104 105
    QPushButton* recenterButton = new QPushButton(this);
    recenterButton->setText("Recenter Camera");

    QCheckBox* lockCameraCheckBox = new QCheckBox(this);
    lockCameraCheckBox->setText("Lock Camera");
    lockCameraCheckBox->setChecked(lockCamera);

106 107
    //positionLabel = new QLabel(this);
    //positionLabel->setText(tr("Waiting for first position update.. "));
pixhawk's avatar
pixhawk committed
108

109 110 111 112 113
    QGridLayout* layout = new QGridLayout(this);
    layout->setMargin(0);
    layout->setSpacing(2);
    layout->addWidget(gridCheckBox, 1, 0);
    layout->addWidget(trailCheckBox, 1, 1);
lm's avatar
lm committed
114 115
    layout->addWidget(waypointsCheckBox, 1, 2);
    layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 3);
116 117 118 119 120
    layout->addWidget(imageryLabel, 1, 4);
    layout->addWidget(imageryComboBox, 1, 5);
    layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 6);
    layout->addWidget(recenterButton, 1, 7);
    layout->addWidget(lockCameraCheckBox, 1, 8);
121 122
    layout->setRowStretch(0, 100);
    layout->setRowStretch(1, 1);
123 124
    layout->setColumnStretch(3, 50);
    layout->setColumnStretch(6, 50);
125
    setLayout(layout);
126

127 128 129 130
    connect(gridCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(showGrid(int)));
    connect(trailCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(showTrail(int)));
131 132
    connect(imageryComboBox, SIGNAL(currentIndexChanged(const QString &)),
            this, SLOT(showImagery(const QString &)));
133 134 135
    connect(recenterButton, SIGNAL(clicked()), this, SLOT(recenterCamera()));
    connect(lockCameraCheckBox, SIGNAL(stateChanged(int)),
            this, SLOT(toggleLockCamera(int)));
136 137
}

lm's avatar
lm committed
138 139 140 141 142 143 144 145 146 147
void
QMap3DWidget::display(void* clientData)
{
    QMap3DWidget* map3d = reinterpret_cast<QMap3DWidget *>(clientData);
    map3d->displayHandler();
}

void
QMap3DWidget::displayHandler(void)
{
lm's avatar
lm committed
148
    if (cheetahModel.data() == 0)
lm's avatar
lm committed
149 150 151 152 153
    {
        cheetahModel.reset(new CheetahModel);
        cheetahModel->init(1.0f, 1.0f, 1.0f);
    }

154 155 156
    float robotX = 0.0f, robotY = 0.0f, robotZ = 0.0f;
    float robotRoll = 0.0f, robotPitch = 0.0f, robotYaw = 0.0f;
    if (uas != NULL)
lm's avatar
lm committed
157
    {
158 159 160 161 162 163
        robotX = uas->getLocalX();
        robotY = uas->getLocalY();
        robotZ = uas->getLocalZ();
        robotRoll = uas->getRoll();
        robotPitch = uas->getPitch();
        robotYaw = uas->getYaw();
lm's avatar
lm committed
164 165
    }

166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184
    if (updateLastUnlockedPose)
    {
        lastUnlockedPose.x = robotX;
        lastUnlockedPose.y = robotY;
        lastUnlockedPose.z = robotZ;

        camOffset.x = 0.0f;
        camOffset.y = 0.0f;
        camOffset.z = 0.0f;

        updateLastUnlockedPose = false;
    }

    if (!lockCamera)
    {
        camOffset.x = robotX - lastUnlockedPose.x;
        camOffset.y = robotY - lastUnlockedPose.y;
        camOffset.z = robotZ - lastUnlockedPose.z;
    }
185

lm's avatar
lm committed
186 187 188 189 190 191 192 193 194 195
    // turn on smooth lines
    glEnable(GL_LINE_SMOOTH);
    glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
    glEnable(GL_BLEND);
    glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);

    // clear window
    glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
    glClear(GL_COLOR_BUFFER_BIT);

196 197 198
    glPushMatrix();
    glTranslatef(camOffset.x, camOffset.y, camOffset.z);

lm's avatar
lm committed
199
    // draw Cheetah model
200
    drawPlatform(robotRoll, robotPitch, robotYaw);
lm's avatar
lm committed
201

202 203 204 205
    if (displayGrid)
    {
        drawGrid();
    }
lm's avatar
lm committed
206

207 208 209 210
    if (displayTrail)
    {
        drawTrail(robotX, robotY, robotZ);
    }
211

212 213 214 215 216
    if (displayTarget)
    {
        drawTarget(robotX, robotY, robotZ);
    }

lm's avatar
lm committed
217 218 219 220 221
    if (displayWaypoints)
    {
        drawWaypoints();
    }

222 223
    if (displayImagery)
    {
224
        drawImagery(robotX, robotY, "32T", true);
225 226
    }

227 228
    glPopMatrix();

229
    // switch to 2D
230 231
    setDisplayMode2D();

232 233
    drawLegend();

234
    // display pose information
235
    glColor4f(0.0f, 0.0f, 0.0f, 1.0f);
236 237
    glBegin(GL_POLYGON);
    glVertex2f(0.0f, 0.0f);
238 239
    glVertex2f(0.0f, 30.0f);
    glVertex2f(getWindowWidth(), 30.0f);
240 241
    glVertex2f(getWindowWidth(), 0.0f);
    glEnd();
242 243 244 245 246 247 248
    glColor4f(0.1f, 0.1f, 0.1f, 1.0f);
    glBegin(GL_POLYGON);
    glVertex2f(0.0f, getWindowHeight());
    glVertex2f(0.0f, getWindowHeight() - 25.0f);
    glVertex2f(getWindowWidth(), getWindowHeight() - 25.0f);
    glVertex2f(getWindowWidth(), getWindowHeight());
    glEnd();
249

250 251 252
    std::pair<float,float> mouseWorldCoords =
            getPositionIn3DMode(getMouseX(), getMouseY());

253 254 255 256 257 258
    // QT QPAINTER OPENGL PAINTING

    QPainter painter;
    painter.begin(this);
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
259
    paintText(QString("x = %1 y = %2 z = %3 r = %4 p = %5 y = %6 Cursor [%7 %8]").arg(robotX, 0, 'f', 2).arg(robotY, 0, 'f', 2).arg(robotZ, 0, 'f', 2).arg(robotRoll, 0, 'f', 2).arg(robotPitch, 0, 'f', 2).arg(robotYaw, 0, 'f', 2).arg( mouseWorldCoords.first + robotX, 0, 'f', 2).arg( mouseWorldCoords.second + robotY, 0, 'f', 2),
260
              QColor(255, 255, 255),
261
              11,
262 263 264 265
              5,
              5,
              &painter);
}
266

267
void QMap3DWidget::drawWaypoints(void) const
lm's avatar
lm committed
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 300 301 302 303 304 305 306 307 308 309
{
    if (uas)
    {
        const QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
        QColor color;

        QPointF lastWaypoint;

        for (int i = 0; i < list.size(); i++)
        {
            QPointF in(list.at(i)->getX(), list.at(i)->getY());
            // Transform from world to body coordinates
            //in = metricWorldToBody(in);

            // DRAW WAYPOINT
            float waypointRadius = 0.1f;// = vwidth / 20.0f * 2.0f;


            // Select color based on if this is the current waypoint
            if (list.at(i)->getCurrent())
            {
                color = QGC::colorCyan;//uas->getColor();

            }
            else
            {
                color = uas->getColor();

            }

            //float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
            // Draw yaw
            // Draw sphere





            static double radius = 0.2;

            glPushMatrix();
            glTranslatef(in.x() - uas->getLocalX(), in.y() - uas->getLocalY(), 0.0f);
310
            glColor3f(1.0f, 0.3f, 0.3f);
lm's avatar
lm committed
311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342
            glLineWidth(1.0f);

//            // Make sure quad object exists
//            static GLUquadricObj* quadObj2;
//            if(!quadObj2) quadObj2 = gluNewQuadric();
//            gluQuadricDrawStyle(quadObj2, GLU_LINE);
//            gluQuadricNormals(quadObj2, GLU_SMOOTH);
//            /* If we ever changed/used the texture or orientation state
//               of quadObj, we'd need to change it to the defaults here
//               with gluQuadricTexture and/or gluQuadricOrientation. */
//            gluSphere(quadObj2, radius, 10, 10);

            wireSphere(radius, 10, 10);

            glPopMatrix();






            // DRAW CONNECTING LINE
            // Draw line from last waypoint to this one
            if (!lastWaypoint.isNull())
            {
                // OpenGL line
            }
            lastWaypoint = in;
        }
    }
}

343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391
void
QMap3DWidget::drawLegend(void)
{
    // draw marker outlines
    glColor3f(1.0f, 1.0f, 1.0f);
    glLineWidth(3.0f);
    glBegin(GL_LINES);
    glVertex2f(20.0f, 60.0f);
    glVertex2f(20.0f, 80.0f);
    glVertex2f(20.0f, 70.0f);
    glVertex2f(100.0f, 70.0f);
    glVertex2f(100.0f, 60.0f);
    glVertex2f(100.0f, 80.0f);
    glEnd();

    // draw markers
    glColor3f(0.0f, 0.0f, 0.0f);
    glLineWidth(1.5f);
    glBegin(GL_LINES);
    glVertex2f(20.0f, 60.0f);
    glVertex2f(20.0f, 80.0f);
    glVertex2f(20.0f, 70.0f);
    glVertex2f(100.0f, 70.0f);
    glVertex2f(100.0f, 60.0f);
    glVertex2f(100.0f, 80.0f);
    glEnd();

    float f = windowHeight / 2.0f / tanf(d2r(cameraParams.cameraFov / 2.0f));
    float dist = cameraPose.distance / f * 80.0f;

    QPainter painter;
    painter.begin(this);
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);

    QColor rgb(255, 255, 255);
    if (imageryComboBox->currentText().compare("Map (Google)") == 0)
    {
        rgb.setRgb(0, 0, 0);
    }

    paintText(QString("%1 m").arg(dist, 0, 'f', 2),
              rgb,
              10,
              25,
              getWindowHeight() - 65,
              &painter);
}

392 393 394
void
QMap3DWidget::paintText(QString text, QColor color, float fontSize,
                        float refX, float refY, QPainter* painter) const
395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416
{
    QPen prevPen = painter->pen();

    float pPositionX = refX;
    float pPositionY = refY;

    QFont font("Bitstream Vera Sans");
    // Enforce minimum font size of 5 pixels
    int fSize = qMax(5, (int)(fontSize));
    font.setPixelSize(fSize);

    QFontMetrics metrics = QFontMetrics(font);
    int border = qMax(4, metrics.leading());
    QRect rect = metrics.boundingRect(0, 0, width() - 2*border, int(height()*0.125),
                                      Qt::AlignLeft | Qt::TextWordWrap, text);
    painter->setPen(color);
    painter->setFont(font);
    painter->setRenderHint(QPainter::TextAntialiasing);
    painter->drawText(pPositionX, pPositionY,
                      rect.width(), rect.height(),
                      Qt::AlignCenter | Qt::TextWordWrap, text);
    painter->setPen(prevPen);
lm's avatar
lm committed
417 418
}

419 420 421
void
QMap3DWidget::mouse(Qt::MouseButton button, MouseState state,
                    int32_t x, int32_t y, void* clientData)
lm's avatar
lm committed
422
{
423 424 425 426 427 428 429 430 431
    QMap3DWidget* map3d = reinterpret_cast<QMap3DWidget *>(clientData);
    map3d->mouseHandler(button, state, x, y);
}

void
QMap3DWidget::mouseHandler(Qt::MouseButton button, MouseState state,
                           int32_t x, int32_t y)
{
    if (button == Qt::RightButton && state == MOUSE_STATE_DOWN)
lm's avatar
lm committed
432
    {
433
        QMenu menu(this);
434
        QAction* targetAction = menu.addAction(tr("Mark as Target"));
435 436
        connect(targetAction, SIGNAL(triggered()), this, SLOT(markTarget()));
        menu.exec(mapToGlobal(QPoint(x, y)));
lm's avatar
lm committed
437 438 439 440 441 442 443 444 445 446 447 448 449
    }
}

void
QMap3DWidget::timer(void* clientData)
{
    QMap3DWidget* map3d = reinterpret_cast<QMap3DWidget *>(clientData);
    map3d->timerHandler();
}

void
QMap3DWidget::timerHandler(void)
{
450 451 452 453 454
    if (imagery.isNull())
    {
        imagery.reset(new Imagery);
    }

lm's avatar
lm committed
455 456 457
    double timeLapsed = getTime() - lastRedrawTime;
    if (timeLapsed > 0.1)
    {
458
        imagery->update();
lm's avatar
lm committed
459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474
        forceRedraw();
        lastRedrawTime = getTime();
    }
    addTimerFunc(100, timer, this);
}

double
QMap3DWidget::getTime(void) const
{
     struct timeval tv;

     gettimeofday(&tv, NULL);

     return static_cast<double>(tv.tv_sec) +
             static_cast<double>(tv.tv_usec) / 1000000.0;
}
475

476 477 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
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void QMap3DWidget::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
QMap3DWidget::markTarget(void)
{
    std::pair<float,float> mouseWorldCoords =
            getPositionIn3DMode(getLastMouseX(), getLastMouseY());

    float robotX = 0.0f, robotY = 0.0f, robotZ = 0.0f;
    if (uas != NULL)
    {
        robotX = uas->getLocalX();
        robotY = uas->getLocalY();
        robotZ = uas->getLocalZ();
    }

    targetPosition.x = mouseWorldCoords.first + robotX;
    targetPosition.y = mouseWorldCoords.second + robotY;
    targetPosition.z = robotZ;

    displayTarget = true;

511 512 513 514 515
    if (uas)
    {
        uas->setTargetPosition(targetPosition.x, targetPosition.y,
                               targetPosition.z, 0.0f);
    }
516 517
}

518 519 520 521 522 523 524 525 526 527 528 529 530
void
QMap3DWidget::showGrid(int32_t state)
{
    if (state == Qt::Checked)
    {
        displayGrid = true;
    }
    else
    {
        displayGrid = false;
    }
}

531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552
void
QMap3DWidget::showImagery(const QString& text)
{
    if (text.compare("None") == 0)
    {
        displayImagery = false;
    }
    else
    {
        if (text.compare("Map (Google)") == 0)
        {
            imagery->setImageryType(Imagery::MAP);
        }
        else if (text.compare("Satellite (Google)") == 0)
        {
            imagery->setImageryType(Imagery::SATELLITE);
        }
        displayImagery = true;
    }
}


553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573
void
QMap3DWidget::showTrail(int32_t state)
{
    if (state == Qt::Checked)
    {
        if (!displayTrail)
        {
            trail.clear();
        }

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

void
QMap3DWidget::recenterCamera(void)
{
574 575
    updateLastUnlockedPose = true;

576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592
    recenter();
}

void
QMap3DWidget::toggleLockCamera(int32_t state)
{
    if (state == Qt::Checked)
    {
        lockCamera = true;
    }
    else
    {
        lockCamera = false;
    }
}

void
593
QMap3DWidget::drawPlatform(float roll, float pitch, float yaw) const
594 595 596
{
    glPushMatrix();

597 598 599
    glRotatef(yaw * 180.0f / M_PI, 0.0f, 0.0f, 1.0f);
    glRotatef(pitch * 180.0f / M_PI, 0.0f, 1.0f, 0.0f);
    glRotatef(roll * 180.0f / M_PI, 1.0f, 0.0f, 0.0f);
600 601

    glLineWidth(3.0f);
602 603 604

    // X AXIS
    glColor3f(1.0f, 0.0f, 0.0f);
605 606 607 608 609
    glBegin(GL_LINES);
    glVertex3f(0.0f, 0.0f, 0.0f);
    glVertex3f(0.3f, 0.0f, 0.0f);
    glEnd();

610 611 612 613 614 615 616 617 618 619 620 621 622 623
    // Y AXIS
    glColor3f(0.0f, 1.0f, 0.0f);
    glBegin(GL_LINES);
    glVertex3f(0.0f, 0.0f, 0.0f);
    glVertex3f(0.0f, 0.15f, 0.0f);
    glEnd();

    // Z AXIS
    glColor3f(0.0f, 0.0f, 1.0f);
    glBegin(GL_LINES);
    glVertex3f(0.0f, 0.0f, 0.0f);
    glVertex3f(0.0f, 0.0f, 0.15f);
    glEnd();

624 625 626 627 628 629
    cheetahModel->draw();

    glPopMatrix();
}

void
630
QMap3DWidget::drawGrid(void) const
631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660
{
    float radius = 10.0f;
    float resolution = 0.25f;

    glPushMatrix();

    // draw a 20m x 20m grid with 0.25m resolution
    glColor3f(0.5f, 0.5f, 0.5f);
    for (float i = -radius; i <= radius; i += resolution)
    {
        if (fabsf(i - roundf(i)) < 0.01f)
        {
            glLineWidth(2.0f);
        }
        else
        {
            glLineWidth(0.25f);
        }

        glBegin(GL_LINES);
        glVertex3f(i, -radius, 0.0f);
        glVertex3f(i, radius, 0.0f);
        glVertex3f(-radius, i, 0.0f);
        glVertex3f(radius, i, 0.0f);
        glEnd();
    }

    glPopMatrix();
}

661 662
void
QMap3DWidget::drawImagery(double originX, double originY, const QString& zone,
663
                          bool prefetch) const
664 665 666 667
{
    glPushMatrix();
    glEnable(GL_BLEND);

668 669
    glTranslatef(0, 0, 0.1);

670
    double viewingRadius = cameraPose.distance / 4000.0 * 3000.0;
671 672 673 674 675
    if (viewingRadius < 100.0)
    {
        viewingRadius = 100.0;
    }

676 677 678 679 680 681 682 683 684 685 686 687
    double minResolution = 0.25;
    double centerResolution = cameraPose.distance / 100.0;
    double maxResolution = 1048576.0;

    if (imageryComboBox->currentText().compare("Map (Google)") == 0)
    {
        minResolution = 0.25;
    }
    else if (imageryComboBox->currentText().compare("Satellite (Google)") == 0)
    {
        minResolution = 0.5;
    }
688 689 690 691 692 693 694 695 696 697 698

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

699 700
    imagery->draw3D(viewingRadius, resolution, originX, originY,
                    cameraPose.xOffset, cameraPose.yOffset, zone);
701 702 703 704 705 706 707

    if (prefetch)
    {
        if (resolution / 2.0 >= minResolution)
        {
            imagery->prefetch3D(viewingRadius / 2.0, resolution / 2.0,
                                originX, originY,
708
                                cameraPose.xOffset, cameraPose.yOffset, zone);
709 710 711 712 713
        }
        if (resolution * 2.0 <= maxResolution)
        {
            imagery->prefetch3D(viewingRadius * 2.0, resolution * 2.0,
                                originX, originY,
714
                                cameraPose.xOffset, cameraPose.yOffset, zone);
715 716 717 718 719 720 721
        }
    }

    glDisable(GL_BLEND);
    glPopMatrix();
}

722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763
void
QMap3DWidget::drawTrail(float x, float y, float z)
{
    bool addToTrail = false;
    if (trail.size() > 0)
    {
        if (fabsf(x - trail[trail.size() - 1].x) > 0.01f ||
            fabsf(y - trail[trail.size() - 1].y) > 0.01f ||
            fabsf(z - trail[trail.size() - 1].z) > 0.01f)
        {
            addToTrail = true;
        }
    }
    else
    {
        addToTrail = true;
    }

    if (addToTrail)
    {
        Pose3D p = {x, y, z};
        if (trail.size() == trail.capacity())
        {
            memcpy(trail.data(), trail.data() + 1,
                   (trail.size() - 1) * sizeof(Pose3D));
            trail[trail.size() - 1] = p;
        }
        else
        {
            trail.append(p);
        }
    }

    glColor3f(1.0f, 0.0f, 0.0f);
    glLineWidth(1.0f);
    glBegin(GL_LINE_STRIP);
    for (int32_t i = 0; i < trail.size(); ++i)
    {
        glVertex3f(trail[i].x - x, trail[i].y - y, trail[i].z - z);
    }
    glEnd();
}
764 765

void
766
QMap3DWidget::drawTarget(float x, float y, float z) const
767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783
{
    static double radius = 0.2;
    static bool expand = true;

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

    glPushMatrix();
    glTranslatef(targetPosition.x - x, targetPosition.y - y, 0.0f);
    glColor3f(0.0f, 0.7f, 1.0f);
    glLineWidth(1.0f);
pixhawk's avatar
pixhawk committed
784

lm's avatar
lm committed
785
    wireSphere(radius, 10, 10);
786 787 788 789 790 791 792 793 794 795 796 797

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

    glPopMatrix();
}