QGCMapWidget.cc 31.5 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"
lm's avatar
lm committed
9 10

QGCMapWidget::QGCMapWidget(QWidget *parent) :
11 12
    mapcontrol::OPMapWidget(parent),
    firingWaypointChange(NULL),
13
    maxUpdateInterval(2.1f), // 2 seconds
14 15 16
    followUAVEnabled(false),
    trailType(mapcontrol::UAVTrailType::ByTimeElapsed),
    trailInterval(2.0f),
17
    followUAVID(0),
18
    mapInitialized(false),
19
    mapPositionInitialized(false),
20
    homeAltitude(0),
21
    zoomBlocked(false),
22
    uas(NULL)
lm's avatar
lm committed
23
{
24
    currWPManager = UASManager::instance()->getActiveUASWaypointManager();
25
    waypointLines.insert(0, new QGraphicsItemGroup(map));
26 27 28 29 30
    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;
31
    // Widget is inactive until shown
32
    defaultGuidedAlt = -1;
33
    loadSettings(false);
34

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

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

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

49
    // Go to options
50 51 52 53 54 55 56 57
    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);
58 59 60 61 62
    // 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);
63 64 65
}
void QGCMapWidget::guidedActionTriggered()
{
66 67 68 69 70
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return;
    }
71 72 73 74 75 76 77 78 79 80
    if (currWPManager)
    {
        if (defaultGuidedAlt == -1)
        {
            if (!guidedAltActionTriggered())
            {
                return;
            }
        }
        // Create new waypoint and send it to the WPManager to send out.
81
        internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y());
82 83 84 85 86 87 88 89 90 91
        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()
{
92 93 94 95 96
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return false;
    }
97 98 99 100 101 102 103 104 105 106 107 108
    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;
}

109 110 111 112 113 114 115 116 117 118
/**
 * @brief QGCMapWidget::setHomeActionTriggered
 */
bool QGCMapWidget::setHomeActionTriggered()
{
    if (!uas)
    {
        QMessageBox::information(0,"Error","Please connect first");
        return false;
    }
119
    UASManagerInterface *uasManager = UASManager::instance();
120 121 122 123
    if (!uasManager) { return false; }

    // Enter an altitude
    bool ok = false;
124
    double alt = QInputDialog::getDouble(this,"Home Altitude","Enter altitude (in meters) of new home location",0.0,0.0,30000.0,2,&ok);
125 126 127
    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.
128 129
    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);
130 131 132 133 134 135 136 137

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

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

    return success;
}

138 139
void QGCMapWidget::mousePressEvent(QMouseEvent *event)
{
140 141 142 143 144 145 146

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

147 148 149 150 151 152 153
    mapcontrol::OPMapWidget::mousePressEvent(event);
}

void QGCMapWidget::mouseReleaseEvent(QMouseEvent *event)
{
    mousePressPos = event->pos();
    mapcontrol::OPMapWidget::mouseReleaseEvent(event);
154 155 156

    // If the mouse is released, we can't be dragging
    if (firingWaypointChange) {
157
        firingWaypointChange->setChanged();
158 159
        firingWaypointChange = NULL;
    }
160 161 162 163 164 165
}

QGCMapWidget::~QGCMapWidget()
{
    SetShowHome(false);	// doing this appears to stop the map lib crashing on exit
    SetShowUAV(false);	//   "          "
166
    storeSettings();
167 168 169 170
}

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

174 175 176
    // Pass on to parent widget
    OPMapWidget::showEvent(event);

177
    // Connect map updates to the adapter slots
178
    connect(this, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(handleMapWaypointEdit(WayPointItem*)), Qt::UniqueConnection);
179

180 181
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)), Qt::UniqueConnection);
182
    connect(UASManager::instance(), SIGNAL(homePositionChanged(double,double,double)), this, SLOT(updateHomePosition(double,double,double)), Qt::UniqueConnection);
183

lm's avatar
lm committed
184 185 186 187
    foreach (UASInterface* uas, UASManager::instance()->getUASList())
    {
        addUAS(uas);
    }
lm's avatar
lm committed
188 189


190 191 192
    if (!mapInitialized)
    {
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(0, 0);
lm's avatar
lm committed
193

194 195
        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
196

197
        SetShowHome(true);					    // display the HOME position on the map
198 199
        Home->SetSafeArea(0);                         // set radius (meters)
        Home->SetShowSafeArea(false);                                         // show the safe area
200
        Home->SetCoord(pos_lat_lon);             // set the HOME position
lm's avatar
lm committed
201

202 203
        setFrameStyle(QFrame::NoFrame);      // no border frame
        setBackgroundBrush(QBrush(Qt::black)); // tile background
lm's avatar
lm committed
204

205 206 207 208 209
        if (!UASManager::instance()->getActiveUAS()) {
            SetCurrentPosition(pos_lat_lon);         // set the map position to default
        }

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

212 213 214
        // Set currently selected system
        activeUASSet(UASManager::instance()->getActiveUAS());
        setFocus();
215

216 217 218
        // Start timer
        connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateGlobalPosition()));
        mapInitialized = true;
219
        //QTimer::singleShot(800, this, SLOT(loadSettings()));
220
    }
221
    updateTimer.start(maxUpdateInterval*1000);
222
    // Update all UAV positions
223
    updateGlobalPosition();
lm's avatar
lm committed
224 225
}

226
void QGCMapWidget::hideEvent(QHideEvent* event)
lm's avatar
lm committed
227
{
228
    updateTimer.stop();
229 230
    storeSettings();
    OPMapWidget::hideEvent(event);
lm's avatar
lm committed
231
}
lm's avatar
lm committed
232

233 234 235 236 237 238 239
void QGCMapWidget::wheelEvent ( QWheelEvent * event )
{
    if (!zoomBlocked) {
        OPMapWidget::wheelEvent(event);
    }
}

240 241 242 243
/**
 * @param changePosition Load also the last position from settings and update the map position.
 */
void QGCMapWidget::loadSettings(bool changePosition)
244 245 246 247 248 249 250 251
{
    // Atlantic Ocean near Africa, coordinate origin
    double lastZoom = 1;
    double lastLat = 0;
    double lastLon = 0;

    QSettings settings;
    settings.beginGroup("QGC_MAPWIDGET");
252 253 254 255 256 257 258 259
    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();
260 261
    settings.endGroup();

262 263 264 265 266
    // SET CORRECT MENU CHECKBOXES
    // Set the correct trail interval
    if (trailType == mapcontrol::UAVTrailType::ByDistance)
    {
        // XXX
267
        qDebug() << "WARNING: Settings loading for trail type (ByDistance) not implemented";
268 269 270 271
    }
    else if (trailType == mapcontrol::UAVTrailType::ByTimeElapsed)
    {
        // XXX
272
        qDebug() << "WARNING: Settings loading for trail type (ByTimeElapsed) not implemented";
273 274
    }

275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
    // 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);
        }
    }

291 292 293
    // SET INITIAL POSITION AND ZOOM
    internals::PointLatLng pos_lat_lon = internals::PointLatLng(lastLat, lastLon);
    SetCurrentPosition(pos_lat_lon);        // set the map position
294
    SetZoom(lastZoom); // set map zoom level
295 296 297 298 299 300 301 302 303 304
}

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());
305 306
    settings.setValue("TRAIL_TYPE", static_cast<int>(trailType));
    settings.setValue("TRAIL_INTERVAL", trailInterval);
307 308 309 310 311 312
    settings.endGroup();
    settings.sync();
}

void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
{
313 314
    // If a waypoint manager is available
    if (currWPManager)
315
    {
316 317 318 319 320 321 322
        // 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());
323
    }
324

lm's avatar
lm committed
325
    OPMapWidget::mouseDoubleClickEvent(event);
326 327 328
}


lm's avatar
lm committed
329 330
/**
 *
331
 * @param uas the UAS/MAV to monitor/display with the map widget
lm's avatar
lm committed
332 333 334
 */
void QGCMapWidget::addUAS(UASInterface* uas)
{
335 336 337
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)),
            this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,double,quint64)), Qt::UniqueConnection);
    connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)), Qt::UniqueConnection);
338 339 340 341 342 343 344 345
    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
346 347
}

348 349 350
void QGCMapWidget::activeUASSet(UASInterface* uas)
{
    // Only execute if proper UAS is set
351
    this->uas = uas;
352 353

    // Disconnect old MAV manager
354 355
    if (currWPManager)
    {
356
        // Disconnect the waypoint manager / data storage from the UI
357 358 359 360
        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*)));
361 362
    }

363 364 365 366 367
    // Attach the new waypoint manager if a new UAS was selected. Otherwise, indicate
    // that no such manager exists.
    if (uas)
    {
        currWPManager = uas->getWaypointManager();
368

369 370 371
        updateSelectedSystem(uas->getUASID());
        followUAVID = uas->getUASID();
        updateWaypointList(uas->getUASID());
372

373
        // Connect the waypoint manager / data storage to the UI
374 375 376 377
        connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)), Qt::UniqueConnection);
        connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)), Qt::UniqueConnection);
        connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)), Qt::UniqueConnection);
        connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)), Qt::UniqueConnection);
378 379 380 381 382 383 384 385 386 387

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

            // Zoom in
            SetZoom(13);

            mapPositionInitialized = true;
        }
388 389 390 391 392
    }
    else
    {
        currWPManager = NULL;
    }
393 394
}

lm's avatar
lm committed
395 396 397 398 399 400 401 402 403
/**
 * 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
 */
404
void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec)
lm's avatar
lm committed
405 406
{
    Q_UNUSED(usec);
407
    Q_UNUSED(altAMSL);
lm's avatar
lm committed
408

409 410
    // Immediate update
    if (maxUpdateInterval == 0)
411
    {
412 413 414 415 416 417 418 419 420
        // 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());
421 422 423 424 425 426 427 428 429 430 431
            // 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);
            }
432 433 434 435
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
436
        uav->SetUAVPos(pos_lat_lon, altWGS84);
437 438
        // Follow status
        if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
439 440
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((uas->getYaw()/M_PI)*180.0f);
441
    }
442
}
lm's avatar
lm committed
443

444 445 446 447 448 449 450 451 452 453 454 455 456 457
/**
 * 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);
458 459
            AddUAV(system->getUASID(), newUAV);
            uav = newUAV;
LM's avatar
LM committed
460 461 462
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
463 464 465 466
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(system->getLatitude(), system->getLongitude());
467
        uav->SetUAVPos(pos_lat_lon, system->getAltitudeAMSL());
468 469
        // Follow status
        if (followUAVEnabled && system->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
470 471 472
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((system->getYaw()/M_PI)*180.0f);
    }
473 474
}

475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494
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());
495
        uav->SetUAVPos(pos_lat_lon, system->getAltitudeAMSL());
496 497 498 499 500 501 502 503 504
        // 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()
{
505
    updateLocalPosition();
506 507
}

508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523

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

/**
524
 * Does not update the system type or configuration, only the selected status
525 526 527 528 529 530 531 532 533 534 535 536 537 538 539
 */
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));
        }
    }
}


540 541 542 543 544 545
// MAP NAVIGATION
void QGCMapWidget::showGoToDialog()
{
    bool ok;
    QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
                                         tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
546
                                         QString("%1,%2").arg(CurrentPosition().Lat(), 0, 'g', 6).arg(CurrentPosition().Lng(), 0, 'g', 6), &ok);
547 548
    if (ok && !text.isEmpty())
    {
549
        QStringList split = text.split(",");
550 551
        if (split.length() == 2)
        {
552 553 554 555 556 557
            bool convert;
            double latitude = split.first().toDouble(&convert);
            ok &= convert;
            double longitude = split.last().toDouble(&convert);
            ok &= convert;

558 559
            if (ok)
            {
560 561 562 563 564 565 566 567 568 569
                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)
{
570
    qDebug() << "HOME SET TO: " << latitude << longitude << altitude;
571 572
    Home->SetCoord(internals::PointLatLng(latitude, longitude));
    Home->SetAltitude(altitude);
573
    homeAltitude = altitude;
574
    SetShowHome(true);                      // display the HOME position on the map
575
    Home->RefreshPos();
576 577
}

578 579 580
void QGCMapWidget::goHome()
{
    SetCurrentPosition(Home->Coord());
581
    SetZoom(17);
582 583
}

584 585 586 587 588 589 590 591 592 593
/**
 * 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);
}

594 595 596 597 598 599 600 601 602 603 604 605 606 607
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();
    }
608 609 610 611 612 613
    else
    {
        RipMap();
        // Set empty area = unselect area
        map->SetSelectedArea(internals::RectLatLng());
    }
614 615
}

616

617 618 619 620 621 622
// WAYPOINT MAP INTERACTION FUNCTIONS

void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
{
    // Block circle updates
    Waypoint* wp = iconsToWaypoints.value(waypoint, NULL);
623 624 625 626 627

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

628 629
    // Update WP values
    internals::PointLatLng pos = waypoint->Coord();
630 631 632

    // Block waypoint signals
    wp->blockSignals(true);
633 634
    wp->setLatitude(pos.Lat());
    wp->setLongitude(pos.Lng());
635
    wp->blockSignals(false);
636

637

638 639 640 641 642
//    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__;
643

644 645 646 647 648 649 650
    // Protect from vicious double update cycle
    if (firingWaypointChange == wp) {
        return;
    }
    // Not in cycle, block now from entering it
    firingWaypointChange = wp;

651
    emit waypointChanged(wp);
652
}
653 654

// WAYPOINT UPDATE FUNCTIONS
655 656

/**
657 658
 * This function is called if a a single waypoint is updated and
 * also if the whole list changes.
659
 */
660
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
661
{
662
    //qDebug() << __FILE__ << __LINE__ << "UPDATING WP FUNCTION CALLED";
663
    // Source of the event was in this widget, do nothing
664 665 666
    if (firingWaypointChange == wp) {
        return;
    }
667 668
    // 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.
669
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
670
    if (currWPManager)
lm's avatar
lm committed
671
    {
672
        // Only accept waypoints in global coordinate frame
lm's avatar
lm committed
673 674
        if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
        {
675 676 677 678 679
            // 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
680
            int wpindex = currWPManager->getGlobalFrameAndNavTypeIndexOf(wp);
681
            // If not found, return (this should never happen, but helps safety)
682
            if (wpindex < 0) return;
683 684 685
            // Mark this wp as currently edited
            firingWaypointChange = wp;

686 687
            qDebug() << "UPDATING WAYPOINT" << wpindex << "IN 2D MAP";

688
            // Check if wp exists yet in map
lm's avatar
lm committed
689 690
            if (!waypointsToIcons.contains(wp))
            {
691
                // Create icon for new WP
692 693 694
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                Waypoint2DIcon* icon = new Waypoint2DIcon(map, this, wp, wpColor, wpindex);
695 696 697 698 699 700
                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
701 702 703 704
                // Add line element if this is NOT the first waypoint
                if (wpindex > 0)
                {
                    // Get predecessor of this WP
705
                    QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
lm's avatar
lm committed
706 707 708 709 710
                    Waypoint* wp1 = wps.at(wpindex-1);
                    mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL);
                    // If we got a valid graphics item, continue
                    if (prevIcon)
                    {
711
                        mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, icon, wpColor, map);
lm's avatar
lm committed
712
                        line->setParentItem(map);
lm's avatar
lm committed
713 714 715 716
                        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                        if (group)
                        {
                            group->addToGroup(line);
lm's avatar
lm committed
717
                            group->setParentItem(map);
lm's avatar
lm committed
718 719 720
                        }
                    }
                }
lm's avatar
lm committed
721 722 723
            }
            else
            {
724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746
                // 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);
747
                }
748 749 750
                // Re-enable signals again
                this->blockSignals(false);
            }
751

752
            firingWaypointChange = NULL;
753

lm's avatar
lm committed
754 755 756
        }
        else
        {
757 758 759 760
            // 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
761
            if (waypointsToIcons.count() > currWPManager->getGlobalFrameAndNavTypeCount())
lm's avatar
lm committed
762
            {
763
                updateWaypointList(uas);
764 765
            }
        }
766
    }
767 768 769 770 771 772 773 774 775
}

/**
 * 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)
{
776
    qDebug() << "UPDATE WP LIST IN 2D MAP CALLED FOR UAS" << uas;
777 778
    // 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
779
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
780
    if (currWPManager)
lm's avatar
lm committed
781
    {
782 783
        // ORDER MATTERS HERE!
        // TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
784

785 786
        qDebug() << "DELETING NOW OLD WPS";

787 788 789 790 791 792 793 794 795 796
        // Delete connecting waypoint lines
        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
        if (group)
        {
            foreach (QGraphicsItem* item, group->childItems())
            {
                delete item;
            }
        }

797 798
        // Delete first all old waypoints
        // this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
799
        QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
800
        foreach (Waypoint* wp, waypointsToIcons.keys())
801
        {
802 803
            if (!wps.contains(wp))
            {
lm's avatar
lm committed
804 805
                // Get icon to work on
                mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
806 807 808 809
                waypointsToIcons.remove(wp);
                iconsToWaypoints.remove(icon);
                WPDelete(icon);
            }
810 811
        }

812 813 814 815 816 817
        // Update all existing waypoints
        foreach (Waypoint* wp, waypointsToIcons.keys())
        {
            // Update remaining waypoints
            updateWaypoint(uas, wp);
        }
818

819 820 821
        // Update all potentially new waypoints
        foreach (Waypoint* wp, wps)
        {
822
            qDebug() << "UPDATING NEW WP" << wp->getId();
823 824 825
            // Update / add only if new
            if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
        }
lm's avatar
lm committed
826 827 828 829 830 831 832 833 834 835 836

        // 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
837 838 839
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, currIcon, wpColor, map);
lm's avatar
lm committed
840
                line->setParentItem(map);
lm's avatar
lm committed
841 842 843 844
                QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                if (group)
                {
                    group->addToGroup(line);
lm's avatar
lm committed
845
                    group->setParentItem(map);
lm's avatar
lm committed
846 847 848 849
                }
            }
            prevIcon = currIcon;
        }
850
    }
lm's avatar
lm committed
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


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