QGCMapWidget.cc 32.1 KB
Newer Older
1
#include <QInputDialog>
lm's avatar
lm committed
2
#include "QGCMapWidget.h"
LM's avatar
LM committed
3
#include "QGCMapToolBar.h"
lm's avatar
lm committed
4
#include "UASInterface.h"
lm's avatar
lm committed
5
#include "UASManager.h"
6
#include "MAV2DIcon.h"
7
#include "Waypoint2DIcon.h"
8
#include "UASWaypointManager.h"
9
#include "ArduPilotMegaMAV.h"
lm's avatar
lm committed
10 11

QGCMapWidget::QGCMapWidget(QWidget *parent) :
12 13
    mapcontrol::OPMapWidget(parent),
    firingWaypointChange(NULL),
14
    maxUpdateInterval(2.1f), // 2 seconds
15 16 17
    followUAVEnabled(false),
    trailType(mapcontrol::UAVTrailType::ByTimeElapsed),
    trailInterval(2.0f),
18
    followUAVID(0),
19
    mapInitialized(false),
20
    mapPositionInitialized(false),
21
    homeAltitude(0),
22
    zoomBlocked(false),
23
    uas(NULL)
lm's avatar
lm committed
24
{
25
    currWPManager = UASManager::instance()->getActiveUASWaypointManager();
26
    waypointLines.insert(0, new QGraphicsItemGroup(map));
27 28 29 30 31
    connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
    connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
    connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
    connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
    offlineMode = true;
32
    // Widget is inactive until shown
33
    defaultGuidedAlt = -1;
34
    loadSettings(false);
35

36 37 38 39
    //handy for debugging:
    //this->SetShowTileGridLines(true);

    //default appears to be Google Hybrid, and is broken currently
40
#if defined MAP_DEFAULT_TYPE_BING
41
    this->SetMapType(MapType::BingHybrid);
42 43 44 45 46
#elif defined MAP_DEFAULT_TYPE_GOOGLE
    this->SetMapType(MapType::GoogleHybrid);
#else
    this->SetMapType(MapType::OpenStreetMap);
#endif
47

48 49
    this->setContextMenuPolicy(Qt::ActionsContextMenu);

50
    // Go to options
51 52 53 54 55 56 57 58
    QAction *guidedaction = new QAction(this);
    guidedaction->setText("Go To Here (Guided Mode)");
    connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered()));
    this->addAction(guidedaction);
    guidedaction = new QAction(this);
    guidedaction->setText("Go To Here Alt (Guided Mode)");
    connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered()));
    this->addAction(guidedaction);
59
    // Point camera option
60 61 62 63
    QAction *cameraaction = new QAction(this);
    cameraaction->setText("Point Camera Here");
    connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
    this->addAction(cameraaction);
64 65 66 67 68
    // Set home location option
    QAction *sethomeaction = new QAction(this);
    sethomeaction->setText("Set Home Location Here");
    connect(sethomeaction,SIGNAL(triggered()),this,SLOT(setHomeActionTriggered()));
    this->addAction(sethomeaction);
69 70 71
}
void QGCMapWidget::guidedActionTriggered()
{
72 73 74 75 76
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return;
    }
77 78 79 80 81 82 83 84 85 86
    if (currWPManager)
    {
        if (defaultGuidedAlt == -1)
        {
            if (!guidedAltActionTriggered())
            {
                return;
            }
        }
        // Create new waypoint and send it to the WPManager to send out.
87
        internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y());
88 89 90 91 92 93 94 95 96 97
        qDebug() << "Guided action requested. Lat:" << pos.Lat() << "Lon:" << pos.Lng();
        Waypoint wp;
        wp.setLatitude(pos.Lat());
        wp.setLongitude(pos.Lng());
        wp.setAltitude(defaultGuidedAlt);
        currWPManager->goToWaypoint(&wp);
    }
}
bool QGCMapWidget::guidedAltActionTriggered()
{
98 99 100 101 102
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return false;
    }
103 104 105 106 107 108 109 110 111 112 113
    bool ok = false;
    int tmpalt = QInputDialog::getInt(this,"Altitude","Enter default altitude (in meters) of destination point for guided mode",100,0,30000,1,&ok);
    if (!ok)
    {
        //Use has chosen cancel. Do not send the waypoint
        return false;
    }
    defaultGuidedAlt = tmpalt;
    guidedActionTriggered();
    return true;
}
114 115
void QGCMapWidget::cameraActionTriggered()
{
116 117 118 119 120
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return;
    }
121 122 123 124
    ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas);
    if (newmav)
    {
        newmav->setMountConfigure(4,true,true,true);
125
        internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y());
126 127 128
        newmav->setMountControl(pos.Lat(),pos.Lng(),100,true);
    }
}
129

130 131 132 133 134 135 136 137 138 139
/**
 * @brief QGCMapWidget::setHomeActionTriggered
 */
bool QGCMapWidget::setHomeActionTriggered()
{
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return false;
    }
140
    UASManagerInterface *uasManager = UASManager::instance();
141 142 143 144
    if (!uasManager) { return false; }

    // Enter an altitude
    bool ok = false;
145
    double alt = QInputDialog::getDouble(this,"Home Altitude","Enter altitude (in meters) of new home location",0.0,0.0,30000.0,2,&ok);
146 147 148
    if (!ok) return false; //Use has chosen cancel. Do not send the waypoint

    // Create new waypoint and send it to the WPManager to send out.
149 150
    internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y());
    qDebug("Set home location sent. Lat: %f, Lon: %f, Alt: %f.", pos.Lat(), pos.Lng(), alt);
151 152 153 154 155 156 157 158

    bool success = uasManager->setHomePositionAndNotify(pos.Lat(),pos.Lng(), alt);

    qDebug() << ((success)? "Set new home location." : "Failed to set new home location.");

    return success;
}

159 160
void QGCMapWidget::mousePressEvent(QMouseEvent *event)
{
161 162 163 164 165 166 167

    // Store right-click event presses separate for context menu
    // TODO add check if click was on map, or popup box.
    if (event->button() == Qt::RightButton) {
        contextMousePressPos = event->pos();
    }

168 169 170 171 172 173 174
    mapcontrol::OPMapWidget::mousePressEvent(event);
}

void QGCMapWidget::mouseReleaseEvent(QMouseEvent *event)
{
    mousePressPos = event->pos();
    mapcontrol::OPMapWidget::mouseReleaseEvent(event);
175 176 177

    // If the mouse is released, we can't be dragging
    if (firingWaypointChange) {
178
        firingWaypointChange->setChanged();
179 180
        firingWaypointChange = NULL;
    }
181 182 183 184 185 186
}

QGCMapWidget::~QGCMapWidget()
{
    SetShowHome(false);	// doing this appears to stop the map lib crashing on exit
    SetShowUAV(false);	//   "          "
187
    storeSettings();
188 189 190 191
}

void QGCMapWidget::showEvent(QShowEvent* event)
{
192
    // Disable OP's standard UAV, we have more than one
LM's avatar
LM committed
193 194
    SetShowUAV(false);

195 196 197
    // Pass on to parent widget
    OPMapWidget::showEvent(event);

198 199 200
    // Connect map updates to the adapter slots
    connect(this, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(handleMapWaypointEdit(WayPointItem*)));

201 202
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)), Qt::UniqueConnection);
203 204
    connect(UASManager::instance(), SIGNAL(homePositionChanged(double,double,double)), this, SLOT(updateHomePosition(double,double,double)));

lm's avatar
lm committed
205 206 207 208
    foreach (UASInterface* uas, UASManager::instance()->getUASList())
    {
        addUAS(uas);
    }
lm's avatar
lm committed
209 210


211 212 213
    if (!mapInitialized)
    {
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(0, 0);
lm's avatar
lm committed
214

215 216
        SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter);	    // set how the mouse wheel zoom functions
        SetFollowMouse(true);				    // we want a contiuous mouse position reading
lm's avatar
lm committed
217

218
        SetShowHome(true);					    // display the HOME position on the map
219 220
        Home->SetSafeArea(0);                         // set radius (meters)
        Home->SetShowSafeArea(false);                                         // show the safe area
221
        Home->SetCoord(pos_lat_lon);             // set the HOME position
lm's avatar
lm committed
222

223 224
        setFrameStyle(QFrame::NoFrame);      // no border frame
        setBackgroundBrush(QBrush(Qt::black)); // tile background
lm's avatar
lm committed
225

226 227 228 229 230
        if (!UASManager::instance()->getActiveUAS()) {
            SetCurrentPosition(pos_lat_lon);         // set the map position to default
        }

        // Set home
231
        updateHomePosition(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
232

233 234 235
        // Set currently selected system
        activeUASSet(UASManager::instance()->getActiveUAS());
        setFocus();
236

237 238 239
        // Start timer
        connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateGlobalPosition()));
        mapInitialized = true;
240
        //QTimer::singleShot(800, this, SLOT(loadSettings()));
241
    }
242
    updateTimer.start(maxUpdateInterval*1000);
243
    // Update all UAV positions
244
    updateGlobalPosition();
lm's avatar
lm committed
245 246
}

247
void QGCMapWidget::hideEvent(QHideEvent* event)
lm's avatar
lm committed
248
{
249
    updateTimer.stop();
250 251
    storeSettings();
    OPMapWidget::hideEvent(event);
lm's avatar
lm committed
252
}
lm's avatar
lm committed
253

254 255 256 257 258 259 260
void QGCMapWidget::wheelEvent ( QWheelEvent * event )
{
    if (!zoomBlocked) {
        OPMapWidget::wheelEvent(event);
    }
}

261 262 263 264
/**
 * @param changePosition Load also the last position from settings and update the map position.
 */
void QGCMapWidget::loadSettings(bool changePosition)
265 266 267 268 269 270 271 272
{
    // Atlantic Ocean near Africa, coordinate origin
    double lastZoom = 1;
    double lastLat = 0;
    double lastLon = 0;

    QSettings settings;
    settings.beginGroup("QGC_MAPWIDGET");
273 274 275 276 277 278 279 280
    if (changePosition)
    {
        lastLat = settings.value("LAST_LATITUDE", lastLat).toDouble();
        lastLon = settings.value("LAST_LONGITUDE", lastLon).toDouble();
        lastZoom = settings.value("LAST_ZOOM", lastZoom).toDouble();
    }
    trailType = static_cast<mapcontrol::UAVTrailType::Types>(settings.value("TRAIL_TYPE", trailType).toInt());
    trailInterval = settings.value("TRAIL_INTERVAL", trailInterval).toFloat();
281 282
    settings.endGroup();

283 284 285 286 287
    // SET CORRECT MENU CHECKBOXES
    // Set the correct trail interval
    if (trailType == mapcontrol::UAVTrailType::ByDistance)
    {
        // XXX
288
        qDebug() << "WARNING: Settings loading for trail type (ByDistance) not implemented";
289 290 291 292
    }
    else if (trailType == mapcontrol::UAVTrailType::ByTimeElapsed)
    {
        // XXX
293
        qDebug() << "WARNING: Settings loading for trail type (ByTimeElapsed) not implemented";
294 295
    }

296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311
    // SET TRAIL TYPE
    foreach (mapcontrol::UAVItem* uav, GetUAVS())
    {
        // Set the correct trail type
        uav->SetTrailType(trailType);
        // Set the correct trail interval
        if (trailType == mapcontrol::UAVTrailType::ByDistance)
        {
            uav->SetTrailDistance(trailInterval);
        }
        else if (trailType == mapcontrol::UAVTrailType::ByTimeElapsed)
        {
            uav->SetTrailTime(trailInterval);
        }
    }

312 313 314
    // SET INITIAL POSITION AND ZOOM
    internals::PointLatLng pos_lat_lon = internals::PointLatLng(lastLat, lastLon);
    SetCurrentPosition(pos_lat_lon);        // set the map position
315
    SetZoom(lastZoom); // set map zoom level
316 317 318 319 320 321 322 323 324 325
}

void QGCMapWidget::storeSettings()
{
    QSettings settings;
    settings.beginGroup("QGC_MAPWIDGET");
    internals::PointLatLng pos = CurrentPosition();
    settings.setValue("LAST_LATITUDE", pos.Lat());
    settings.setValue("LAST_LONGITUDE", pos.Lng());
    settings.setValue("LAST_ZOOM", ZoomReal());
326 327
    settings.setValue("TRAIL_TYPE", static_cast<int>(trailType));
    settings.setValue("TRAIL_INTERVAL", trailInterval);
328 329 330 331 332 333
    settings.endGroup();
    settings.sync();
}

void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
{
334 335
    // If a waypoint manager is available
    if (currWPManager)
336
    {
337 338 339 340 341 342 343
        // Create new waypoint
        internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y());
        Waypoint* wp = currWPManager->createWaypoint();
        wp->setLatitude(pos.Lat());
        wp->setLongitude(pos.Lng());
        wp->setFrame((MAV_FRAME)currWPManager->getFrameRecommendation());
        wp->setAltitude(currWPManager->getAltitudeRecommendation());
344
    }
345

lm's avatar
lm committed
346
    OPMapWidget::mouseDoubleClickEvent(event);
347 348 349
}


lm's avatar
lm committed
350 351
/**
 *
352
 * @param uas the UAS/MAV to monitor/display with the map widget
lm's avatar
lm committed
353 354 355
 */
void QGCMapWidget::addUAS(UASInterface* uas)
{
356
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,double,quint64)));
357
    connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)));
358 359 360 361 362 363 364 365
    if (!waypointLines.value(uas->getUASID(), NULL)) {
        waypointLines.insert(uas->getUASID(), new QGraphicsItemGroup(map));
    } else {
        foreach (QGraphicsItem* item, waypointLines.value(uas->getUASID())->childItems())
        {
            delete item;
        }
    }
lm's avatar
lm committed
366 367
}

368 369 370
void QGCMapWidget::activeUASSet(UASInterface* uas)
{
    // Only execute if proper UAS is set
371
    this->uas = uas;
372 373

    // Disconnect old MAV manager
374 375
    if (currWPManager)
    {
376
        // Disconnect the waypoint manager / data storage from the UI
377 378 379 380
        disconnect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
        disconnect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
        disconnect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
        disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
381 382
    }

383 384 385 386 387
    // Attach the new waypoint manager if a new UAS was selected. Otherwise, indicate
    // that no such manager exists.
    if (uas)
    {
        currWPManager = uas->getWaypointManager();
388

389 390 391
        updateSelectedSystem(uas->getUASID());
        followUAVID = uas->getUASID();
        updateWaypointList(uas->getUASID());
392

393 394 395 396 397
        // Connect the waypoint manager / data storage to the UI
        connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
        connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
        connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
        connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
398 399 400 401 402 403 404 405 406 407

        if (!mapPositionInitialized) {
            internals::PointLatLng pos_lat_lon = internals::PointLatLng(uas->getLatitude(), uas->getLongitude());
            SetCurrentPosition(pos_lat_lon);

            // Zoom in
            SetZoom(13);

            mapPositionInitialized = true;
        }
408 409 410 411 412
    }
    else
    {
        currWPManager = NULL;
    }
413 414
}

lm's avatar
lm committed
415 416 417 418 419 420 421 422 423
/**
 * Updates the global position of one MAV and append the last movement to the trail
 *
 * @param uas The unmanned air system
 * @param lat Latitude in WGS84 ellipsoid
 * @param lon Longitutde in WGS84 ellipsoid
 * @param alt Altitude over mean sea level
 * @param usec Timestamp of the position message in milliseconds FIXME will move to microseconds
 */
424
void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec)
lm's avatar
lm committed
425 426
{
    Q_UNUSED(usec);
427
    Q_UNUSED(altAMSL);
lm's avatar
lm committed
428

429 430
    // Immediate update
    if (maxUpdateInterval == 0)
431
    {
432 433 434 435 436 437 438 439 440
        // Get reference to graphic UAV item
        mapcontrol::UAVItem* uav = GetUAV(uas->getUASID());
        // Check if reference is valid, else create a new one
        if (uav == NULL)
        {
            MAV2DIcon* newUAV = new MAV2DIcon(map, this, uas);
            newUAV->setParentItem(map);
            UAVS.insert(uas->getUASID(), newUAV);
            uav = GetUAV(uas->getUASID());
441 442 443 444 445 446 447 448 449 450 451
            // Set the correct trail type
            uav->SetTrailType(trailType);
            // Set the correct trail interval
            if (trailType == mapcontrol::UAVTrailType::ByDistance)
            {
                uav->SetTrailDistance(trailInterval);
            }
            else if (trailType == mapcontrol::UAVTrailType::ByTimeElapsed)
            {
                uav->SetTrailTime(trailInterval);
            }
452 453 454 455
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
456
        uav->SetUAVPos(pos_lat_lon, altWGS84);
457 458
        // Follow status
        if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
459 460
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((uas->getYaw()/M_PI)*180.0f);
461
    }
462
}
lm's avatar
lm committed
463

464 465 466 467 468 469 470 471 472 473 474 475 476 477
/**
 * Pulls in the positions of all UAVs from the UAS manager
 */
void QGCMapWidget::updateGlobalPosition()
{
    QList<UASInterface*> systems = UASManager::instance()->getUASList();
    foreach (UASInterface* system, systems)
    {
        // Get reference to graphic UAV item
        mapcontrol::UAVItem* uav = GetUAV(system->getUASID());
        // Check if reference is valid, else create a new one
        if (uav == NULL)
        {
            MAV2DIcon* newUAV = new MAV2DIcon(map, this, system);
478 479
            AddUAV(system->getUASID(), newUAV);
            uav = newUAV;
LM's avatar
LM committed
480 481 482
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
483 484 485 486
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(system->getLatitude(), system->getLongitude());
487
        uav->SetUAVPos(pos_lat_lon, system->getAltitudeAMSL());
488 489
        // Follow status
        if (followUAVEnabled && system->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
490 491 492
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((system->getYaw()/M_PI)*180.0f);
    }
493 494
}

495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514
void QGCMapWidget::updateLocalPosition()
{
    QList<UASInterface*> systems = UASManager::instance()->getUASList();
    foreach (UASInterface* system, systems)
    {
        // Get reference to graphic UAV item
        mapcontrol::UAVItem* uav = GetUAV(system->getUASID());
        // Check if reference is valid, else create a new one
        if (uav == NULL)
        {
            MAV2DIcon* newUAV = new MAV2DIcon(map, this, system);
            AddUAV(system->getUASID(), newUAV);
            uav = newUAV;
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(system->getLatitude(), system->getLongitude());
515
        uav->SetUAVPos(pos_lat_lon, system->getAltitudeAMSL());
516 517 518 519 520 521 522 523 524
        // Follow status
        if (followUAVEnabled && system->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((system->getYaw()/M_PI)*180.0f);
    }
}

void QGCMapWidget::updateLocalPositionEstimates()
{
525
    updateLocalPosition();
526 527
}

528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543

void QGCMapWidget::updateSystemSpecs(int uas)
{
    foreach (mapcontrol::UAVItem* p, UAVS.values())
    {
        MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
        if (icon && icon->getUASId() == uas)
        {
            // Set new airframe
            icon->setAirframe(UASManager::instance()->getUASForId(uas)->getAirframe());
            icon->drawIcon();
        }
    }
}

/**
544
 * Does not update the system type or configuration, only the selected status
545 546 547 548 549 550 551 552 553 554 555 556 557 558 559
 */
void QGCMapWidget::updateSelectedSystem(int uas)
{
    foreach (mapcontrol::UAVItem* p, UAVS.values())
    {
        MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
        if (icon)
        {
            // Set as selected if ids match
            icon->setSelectedUAS((icon->getUASId() == uas));
        }
    }
}


560 561 562 563 564 565
// MAP NAVIGATION
void QGCMapWidget::showGoToDialog()
{
    bool ok;
    QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
                                         tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
566
                                         QString("%1,%2").arg(CurrentPosition().Lat(), 0, 'g', 6).arg(CurrentPosition().Lng(), 0, 'g', 6), &ok);
567 568
    if (ok && !text.isEmpty())
    {
569
        QStringList split = text.split(",");
570 571
        if (split.length() == 2)
        {
572 573 574 575 576 577
            bool convert;
            double latitude = split.first().toDouble(&convert);
            ok &= convert;
            double longitude = split.last().toDouble(&convert);
            ok &= convert;

578 579
            if (ok)
            {
580 581 582 583 584 585 586 587 588 589
                internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude);
                SetCurrentPosition(pos_lat_lon);        // set the map position
            }
        }
    }
}


void QGCMapWidget::updateHomePosition(double latitude, double longitude, double altitude)
{
590
    qDebug() << "HOME SET TO: " << latitude << longitude << altitude;
591 592
    Home->SetCoord(internals::PointLatLng(latitude, longitude));
    Home->SetAltitude(altitude);
593
    homeAltitude = altitude;
594
    SetShowHome(true);                      // display the HOME position on the map
595
    Home->RefreshPos();
596 597
}

598 599 600
void QGCMapWidget::goHome()
{
    SetCurrentPosition(Home->Coord());
601
    SetZoom(17);
602 603
}

604 605 606 607 608 609 610 611 612 613
/**
 * Limits the update rate on the specified interval. Set to zero (0) to run at maximum
 * telemetry speed. Recommended rate is 2 s.
 */
void QGCMapWidget::setUpdateRateLimit(float seconds)
{
    maxUpdateInterval = seconds;
    updateTimer.start(maxUpdateInterval*1000);
}

614 615 616 617 618 619 620 621 622 623 624 625 626 627
void QGCMapWidget::cacheVisibleRegion()
{
    internals::RectLatLng rect = map->SelectedArea();

    if (rect.IsEmpty())
    {
        QMessageBox msgBox(this);
        msgBox.setIcon(QMessageBox::Information);
        msgBox.setText("Cannot cache tiles for offline use");
        msgBox.setInformativeText("Please select an area first by holding down SHIFT or ALT and selecting the area with the left mouse button.");
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
628 629 630 631 632 633
    else
    {
        RipMap();
        // Set empty area = unselect area
        map->SetSelectedArea(internals::RectLatLng());
    }
634 635
}

636

637 638 639 640 641 642
// WAYPOINT MAP INTERACTION FUNCTIONS

void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
{
    // Block circle updates
    Waypoint* wp = iconsToWaypoints.value(waypoint, NULL);
643 644 645 646 647

    // Delete UI element if wp doesn't exist
    if (!wp)
        WPDelete(waypoint);

648 649
    // Update WP values
    internals::PointLatLng pos = waypoint->Coord();
650 651 652

    // Block waypoint signals
    wp->blockSignals(true);
653 654
    wp->setLatitude(pos.Lat());
    wp->setLongitude(pos.Lng());
655
    wp->blockSignals(false);
656

657

658 659 660 661 662
//    internals::PointLatLng coord = waypoint->Coord();
//    QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + "   " + QString::number(coord.Lng(), 'f', 6);
//    qDebug() << "MAP WP COORD (MAP):" << coord_str << __FILE__ << __LINE__;
//    QString wp_str = QString::number(wp->getLatitude(), 'f', 6) + "   " + QString::number(wp->getLongitude(), 'f', 6);
//    qDebug() << "MAP WP COORD (WP):" << wp_str << __FILE__ << __LINE__;
663

664 665 666 667 668 669 670
    // Protect from vicious double update cycle
    if (firingWaypointChange == wp) {
        return;
    }
    // Not in cycle, block now from entering it
    firingWaypointChange = wp;

671
    emit waypointChanged(wp);
672
}
673 674

// WAYPOINT UPDATE FUNCTIONS
675 676

/**
677 678
 * This function is called if a a single waypoint is updated and
 * also if the whole list changes.
679
 */
680
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
681
{
682
    //qDebug() << __FILE__ << __LINE__ << "UPDATING WP FUNCTION CALLED";
683
    // Source of the event was in this widget, do nothing
684 685 686
    if (firingWaypointChange == wp) {
        return;
    }
687 688
    // Currently only accept waypoint updates from the UAS in focus
    // this has to be changed to accept read-only updates from other systems as well.
689
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
690
    if (currWPManager)
lm's avatar
lm committed
691
    {
692
        // Only accept waypoints in global coordinate frame
lm's avatar
lm committed
693 694
        if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
        {
695 696 697 698 699
            // We're good, this is a global waypoint

            // Get the index of this waypoint
            // note the call to getGlobalFrameAndNavTypeIndexOf()
            // as we're only handling global waypoints
700
            int wpindex = currWPManager->getGlobalFrameAndNavTypeIndexOf(wp);
701
            // If not found, return (this should never happen, but helps safety)
702
            if (wpindex < 0) return;
703 704 705
            // Mark this wp as currently edited
            firingWaypointChange = wp;

706 707
            qDebug() << "UPDATING WAYPOINT" << wpindex << "IN 2D MAP";

708
            // Check if wp exists yet in map
lm's avatar
lm committed
709 710
            if (!waypointsToIcons.contains(wp))
            {
711
                // Create icon for new WP
712 713 714
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                Waypoint2DIcon* icon = new Waypoint2DIcon(map, this, wp, wpColor, wpindex);
715 716 717 718 719 720
                ConnectWP(icon);
                icon->setParentItem(map);
                // Update maps to allow inverse data association
                waypointsToIcons.insert(wp, icon);
                iconsToWaypoints.insert(icon, wp);

lm's avatar
lm committed
721 722 723 724
                // Add line element if this is NOT the first waypoint
                if (wpindex > 0)
                {
                    // Get predecessor of this WP
725
                    QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
lm's avatar
lm committed
726 727 728 729 730
                    Waypoint* wp1 = wps.at(wpindex-1);
                    mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL);
                    // If we got a valid graphics item, continue
                    if (prevIcon)
                    {
731
                        mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, icon, wpColor, map);
lm's avatar
lm committed
732
                        line->setParentItem(map);
lm's avatar
lm committed
733 734 735 736
                        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                        if (group)
                        {
                            group->addToGroup(line);
lm's avatar
lm committed
737
                            group->setParentItem(map);
lm's avatar
lm committed
738 739 740
                        }
                    }
                }
lm's avatar
lm committed
741 742 743
            }
            else
            {
744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766
                // Waypoint exists, block it's signals and update it
                mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
                // Make sure we don't die on a null pointer
                // this should never happen, just a precaution
                if (!icon) return;
                // Block outgoing signals to prevent an infinite signal loop
                // should not happen, just a precaution
                this->blockSignals(true);
                // Update the WP
                Waypoint2DIcon* wpicon = dynamic_cast<Waypoint2DIcon*>(icon);
                if (wpicon)
                {
                    // Let icon read out values directly from waypoint
                    icon->SetNumber(wpindex);
                    wpicon->updateWaypoint();
                }
                else
                {
                    // Use safe standard interfaces for non Waypoint-class based wps
                    icon->SetCoord(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()));
                    icon->SetAltitude(wp->getAltitude());
                    icon->SetHeading(wp->getYaw());
                    icon->SetNumber(wpindex);
767
                }
768 769 770
                // Re-enable signals again
                this->blockSignals(false);
            }
771

772
            firingWaypointChange = NULL;
773

lm's avatar
lm committed
774 775 776
        }
        else
        {
777 778 779 780
            // Check if the index of this waypoint is larger than the global
            // waypoint list. This implies that the coordinate frame of this
            // waypoint was changed and the list containing only global
            // waypoints was shortened. Thus update the whole list
781
            if (waypointsToIcons.count() > currWPManager->getGlobalFrameAndNavTypeCount())
lm's avatar
lm committed
782
            {
783
                updateWaypointList(uas);
784 785
            }
        }
786
    }
787 788 789 790 791 792 793 794 795
}

/**
 * Update the whole list of waypoints. This is e.g. necessary if the list order changed.
 * The UAS manager will emit the appropriate signal whenever updating the list
 * is necessary.
 */
void QGCMapWidget::updateWaypointList(int uas)
{
796
    qDebug() << "UPDATE WP LIST IN 2D MAP CALLED FOR UAS" << uas;
797 798
    // Currently only accept waypoint updates from the UAS in focus
    // this has to be changed to accept read-only updates from other systems as well.
lm's avatar
lm committed
799
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
800
    if (currWPManager)
lm's avatar
lm committed
801
    {
802 803
        // ORDER MATTERS HERE!
        // TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
804

805 806
        qDebug() << "DELETING NOW OLD WPS";

807 808 809 810 811 812 813 814 815 816
        // Delete connecting waypoint lines
        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
        if (group)
        {
            foreach (QGraphicsItem* item, group->childItems())
            {
                delete item;
            }
        }

817 818
        // Delete first all old waypoints
        // this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
819
        QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
820
        foreach (Waypoint* wp, waypointsToIcons.keys())
821
        {
822 823
            if (!wps.contains(wp))
            {
lm's avatar
lm committed
824 825
                // Get icon to work on
                mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
826 827 828 829
                waypointsToIcons.remove(wp);
                iconsToWaypoints.remove(icon);
                WPDelete(icon);
            }
830 831
        }

832 833 834 835 836 837
        // Update all existing waypoints
        foreach (Waypoint* wp, waypointsToIcons.keys())
        {
            // Update remaining waypoints
            updateWaypoint(uas, wp);
        }
838

839 840 841
        // Update all potentially new waypoints
        foreach (Waypoint* wp, wps)
        {
842
            qDebug() << "UPDATING NEW WP" << wp->getId();
843 844 845
            // Update / add only if new
            if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
        }
lm's avatar
lm committed
846 847 848 849 850 851 852 853 854 855 856

        // Add line element if this is NOT the first waypoint
        mapcontrol::WayPointItem* prevIcon = NULL;
        foreach (Waypoint* wp, wps)
        {
            mapcontrol::WayPointItem* currIcon = waypointsToIcons.value(wp, NULL);
            // Do not work on first waypoint, but only increment counter
            // do not continue if icon is invalid
            if (prevIcon && currIcon)
            {
                // If we got a valid graphics item, continue
857 858 859
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, currIcon, wpColor, map);
lm's avatar
lm committed
860
                line->setParentItem(map);
lm's avatar
lm committed
861 862 863 864
                QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                if (group)
                {
                    group->addToGroup(line);
lm's avatar
lm committed
865
                    group->setParentItem(map);
lm's avatar
lm committed
866 867 868 869
                }
            }
            prevIcon = currIcon;
        }
870
    }
lm's avatar
lm committed
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


//// ADAPTER / HELPER FUNCTIONS
//float QGCMapWidget::metersToPixels(double meters)
//{
//    return meters/map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat());
//}

//double QGCMapWidget::headingP1P2(internals::PointLatLng p1, internals::PointLatLng p2)
//{
//    double lat1 = p1.Lat() * deg_to_rad;
//    double lon1 = p2.Lng() * deg_to_rad;

//    double lat2 = p2.Lat() * deg_to_rad;
//    double lon2 = p2.Lng() * deg_to_rad;

//    double delta_lon = lon2 - lon1;

//    double y = sin(delta_lon) * cos(lat2);
//    double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(delta_lon);
//    double heading = atan2(y, x) * rad_to_deg;

//    heading += 360;
//    while (heading < 0) bear += 360;
//    while (heading >= 360) bear -= 360;

//    return heading;
//}

//internals::PointLatLng QGCMapWidget::targetLatLon(internals::PointLatLng source, double heading, double dist)
//{
//    double lat1 = source.Lat() * deg_to_rad;
//    double lon1 = source.Lng() * deg_to_rad;

//    heading *= deg_to_rad;

//    double ad = dist / earth_mean_radius;

//    double lat2 = asin(sin(lat1) * cos(ad) + cos(lat1) * sin(ad) * cos(heading));
//    double lon2 = lon1 + atan2(sin(bear) * sin(ad) * cos(lat1), cos(ad) - sin(lat1) * sin(lat2));

//    return internals::PointLatLng(lat2 * rad_to_deg, lon2 * rad_to_deg);
//}