QGCMapWidget.cc 25.2 KB
Newer Older
lm's avatar
lm committed
1
#include "QGCMapWidget.h"
LM's avatar
LM committed
2
#include "QGCMapToolBar.h"
lm's avatar
lm committed
3
#include "UASInterface.h"
lm's avatar
lm committed
4
#include "UASManager.h"
5
#include "MAV2DIcon.h"
6
#include "Waypoint2DIcon.h"
7
#include "UASWaypointManager.h"
lm's avatar
lm committed
8 9

QGCMapWidget::QGCMapWidget(QWidget *parent) :
10 11 12
    mapcontrol::OPMapWidget(parent),
    currWPManager(NULL),
    firingWaypointChange(NULL),
13
    maxUpdateInterval(2.1f), // 2 seconds
14 15 16
    followUAVEnabled(false),
    trailType(mapcontrol::UAVTrailType::ByTimeElapsed),
    trailInterval(2.0f),
17
    followUAVID(0),
18 19
    mapInitialized(false),
    homeAltitude(0)
lm's avatar
lm committed
20
{
21
    // Widget is inactive until shown
22
    loadSettings(false);
23 24 25 26 27 28
}

QGCMapWidget::~QGCMapWidget()
{
    SetShowHome(false);	// doing this appears to stop the map lib crashing on exit
    SetShowUAV(false);	//   "          "
29
    storeSettings();
30 31 32 33
}

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

37 38 39
    // Pass on to parent widget
    OPMapWidget::showEvent(event);

40 41
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)), Qt::UniqueConnection);
42 43
    connect(UASManager::instance(), SIGNAL(homePositionChanged(double,double,double)), this, SLOT(updateHomePosition(double,double,double)));

lm's avatar
lm committed
44 45 46 47
    foreach (UASInterface* uas, UASManager::instance()->getUASList())
    {
        addUAS(uas);
    }
lm's avatar
lm committed
48 49


50 51 52
    if (!mapInitialized)
    {
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(0, 0);
lm's avatar
lm committed
53

54 55
        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
56

57 58 59 60
        SetShowHome(true);					    // display the HOME position on the map
        Home->SetSafeArea(30);                         // set radius (meters)
        Home->SetShowSafeArea(true);                                         // show the safe area
        Home->SetCoord(pos_lat_lon);             // set the HOME position
lm's avatar
lm committed
61

62 63
        setFrameStyle(QFrame::NoFrame);      // no border frame
        setBackgroundBrush(QBrush(Qt::black)); // tile background
lm's avatar
lm committed
64

65 66
        // Set current home position
        updateHomePosition(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
67

68 69
        // Set currently selected system
        activeUASSet(UASManager::instance()->getActiveUAS());
70

71 72
        // Connect map updates to the adapter slots
        connect(this, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(handleMapWaypointEdit(WayPointItem*)));
73

74 75
        SetCurrentPosition(pos_lat_lon);         // set the map position
        setFocus();
76

77 78 79
        // Start timer
        connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateGlobalPosition()));
        mapInitialized = true;
80
        //QTimer::singleShot(800, this, SLOT(loadSettings()));
81
    }
82
    updateTimer.start(maxUpdateInterval*1000);
83
    // Update all UAV positions
84
    updateGlobalPosition();
lm's avatar
lm committed
85 86
}

87
void QGCMapWidget::hideEvent(QHideEvent* event)
lm's avatar
lm committed
88
{
89
    updateTimer.stop();
90 91
    storeSettings();
    OPMapWidget::hideEvent(event);
lm's avatar
lm committed
92
}
lm's avatar
lm committed
93

94 95 96 97
/**
 * @param changePosition Load also the last position from settings and update the map position.
 */
void QGCMapWidget::loadSettings(bool changePosition)
98 99 100 101 102 103 104 105
{
    // Atlantic Ocean near Africa, coordinate origin
    double lastZoom = 1;
    double lastLat = 0;
    double lastLon = 0;

    QSettings settings;
    settings.beginGroup("QGC_MAPWIDGET");
106 107 108 109 110 111 112 113
    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();
114 115
    settings.endGroup();

116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131
    // 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);
        }
    }

132 133 134
    // SET INITIAL POSITION AND ZOOM
    internals::PointLatLng pos_lat_lon = internals::PointLatLng(lastLat, lastLon);
    SetCurrentPosition(pos_lat_lon);        // set the map position
135
    SetZoom(lastZoom); // set map zoom level
136 137 138 139 140 141 142 143 144 145
}

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());
146 147
    settings.setValue("TRAIL_TYPE", static_cast<int>(trailType));
    settings.setValue("TRAIL_INTERVAL", trailInterval);
148 149 150 151 152 153
    settings.endGroup();
    settings.sync();
}

void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
{
lm's avatar
lm committed
154

lm's avatar
lm committed
155
    // FIXME HACK!
lm's avatar
lm committed
156
    //if (currEditMode == EDIT_MODE_WAYPOINTS)
157 158 159 160 161
    {
        // If a waypoint manager is available
        if (currWPManager)
        {
            // Create new waypoint
lm's avatar
lm committed
162
            internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y());
163
            Waypoint* wp = currWPManager->createWaypoint();
164 165
            //            wp->blockSignals(true);
            //            wp->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
166 167
            wp->setLatitude(pos.Lat());
            wp->setLongitude(pos.Lng());
lm's avatar
lm committed
168
            wp->setAltitude(0);
169
            //            wp->blockSignals(false);
170
            //            currWPManager->notifyOfChangeEditable(wp);
171 172
        }
    }
lm's avatar
lm committed
173
    OPMapWidget::mouseDoubleClickEvent(event);
174 175 176
}


lm's avatar
lm committed
177 178
/**
 *
179
 * @param uas the UAS/MAV to monitor/display with the map widget
lm's avatar
lm committed
180 181 182 183
 */
void QGCMapWidget::addUAS(UASInterface* uas)
{
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
184
    connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)));
lm's avatar
lm committed
185 186
}

187 188 189
void QGCMapWidget::activeUASSet(UASInterface* uas)
{
    // Only execute if proper UAS is set
190
    if (!uas) return;
191 192

    // Disconnect old MAV manager
193 194
    if (currWPManager)
    {
195
        // Disconnect the waypoint manager / data storage from the UI
196 197 198 199
        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*)));
200 201
    }

202 203
    if (uas)
    {
204 205 206
        currWPManager = uas->getWaypointManager();

        // Connect the waypoint manager / data storage to the UI
207 208 209 210
        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*)));
211

212
        updateSelectedSystem(uas->getUASID());
213
        followUAVID = uas->getUASID();
214 215 216

        // Delete all waypoints and add waypoint from new system
        updateWaypointList(uas->getUASID());
217 218 219
    }
}

lm's avatar
lm committed
220 221 222 223 224 225 226 227 228 229 230 231 232
/**
 * 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
 */
void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
    Q_UNUSED(usec);

233 234
    // Immediate update
    if (maxUpdateInterval == 0)
235
    {
236 237 238 239 240 241 242 243 244
        // 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());
LM's avatar
LM committed
245 246 247
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
248 249 250 251 252
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
        uav->SetUAVPos(pos_lat_lon, alt);
253 254
        // Follow status
        if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
255 256
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((uas->getYaw()/M_PI)*180.0f);
257
    }
258
}
lm's avatar
lm committed
259

260 261 262 263 264 265 266 267 268 269 270 271 272 273
/**
 * 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);
274 275
            AddUAV(system->getUASID(), newUAV);
            uav = newUAV;
LM's avatar
LM committed
276 277 278
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
279 280 281 282 283
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(system->getLatitude(), system->getLongitude());
        uav->SetUAVPos(pos_lat_lon, system->getAltitude());
284 285
        // Follow status
        if (followUAVEnabled && system->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
286 287 288
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((system->getYaw()/M_PI)*180.0f);
    }
289 290
}

291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320
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());
        uav->SetUAVPos(pos_lat_lon, system->getAltitude());
        // 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()
{
321
    updateLocalPosition();
322 323
}

324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339

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

/**
340
 * Does not update the system type or configuration, only the selected status
341 342 343 344 345 346 347 348 349 350 351 352 353 354 355
 */
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));
        }
    }
}


356 357 358 359 360 361
// MAP NAVIGATION
void QGCMapWidget::showGoToDialog()
{
    bool ok;
    QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
                                         tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
362
                                         QString("%1,%2").arg(CurrentPosition().Lat(), 0, 'g', 6).arg(CurrentPosition().Lng(), 0, 'g', 6), &ok);
363 364
    if (ok && !text.isEmpty())
    {
365
        QStringList split = text.split(",");
366 367
        if (split.length() == 2)
        {
368 369 370 371 372 373
            bool convert;
            double latitude = split.first().toDouble(&convert);
            ok &= convert;
            double longitude = split.last().toDouble(&convert);
            ok &= convert;

374 375
            if (ok)
            {
376 377 378 379 380 381 382 383 384 385 386 387
                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)
{
    Home->SetCoord(internals::PointLatLng(latitude, longitude));
    Home->SetAltitude(altitude);
388
    homeAltitude = altitude;
389 390 391
    SetShowHome(true);                      // display the HOME position on the map
}

392 393 394 395 396
void QGCMapWidget::goHome()
{
    SetCurrentPosition(Home->Coord());
}

397 398 399 400 401 402 403 404 405 406
/**
 * 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);
}

407 408 409 410 411 412 413 414 415 416 417 418 419 420
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();
    }
421 422 423 424 425 426
    else
    {
        RipMap();
        // Set empty area = unselect area
        map->SetSelectedArea(internals::RectLatLng());
    }
427 428
}

429

430 431 432 433 434 435 436
// WAYPOINT MAP INTERACTION FUNCTIONS

void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
{
    // Block circle updates
    Waypoint* wp = iconsToWaypoints.value(waypoint, NULL);
    // Protect from vicious double update cycle
437
    if (firingWaypointChange == wp) return;
438 439
    // Not in cycle, block now from entering it
    firingWaypointChange = wp;
440
    // // qDebug() << "UPDATING WP FROM MAP";
441 442 443

    // Update WP values
    internals::PointLatLng pos = waypoint->Coord();
444 445 446

    // Block waypoint signals
    wp->blockSignals(true);
447 448
    wp->setLatitude(pos.Lat());
    wp->setLongitude(pos.Lng());
449 450 451
    // XXX Magic values
    wp->setAltitude(homeAltitude + 50.0f);
    wp->setAcceptanceRadius(10.0f);
452
    wp->blockSignals(false);
453

454

455 456
    internals::PointLatLng coord = waypoint->Coord();
    QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + "   " + QString::number(coord.Lng(), 'f', 6);
457
    // // qDebug() << "MAP WP COORD (MAP):" << coord_str << __FILE__ << __LINE__;
458
    QString wp_str = QString::number(wp->getLatitude(), 'f', 6) + "   " + QString::number(wp->getLongitude(), 'f', 6);
459
    // // qDebug() << "MAP WP COORD (WP):" << wp_str << __FILE__ << __LINE__;
460

461
    firingWaypointChange = NULL;
462 463

    emit waypointChanged(wp);
464
}
465 466

// WAYPOINT UPDATE FUNCTIONS
467 468

/**
469 470
 * This function is called if a a single waypoint is updated and
 * also if the whole list changes.
471
 */
472
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
473
{
474
    qDebug() << "UPDATING WP FUNCTION CALLED";
475 476
    // Source of the event was in this widget, do nothing
    if (firingWaypointChange == wp) return;
477 478
    // 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.
479
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
lm's avatar
lm committed
480 481
    if (uasInstance->getWaypointManager() == currWPManager || uas == -1)
    {
482
        // Only accept waypoints in global coordinate frame
lm's avatar
lm committed
483 484
        if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
        {
485 486 487 488 489
            // 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
490
            int wpindex = currWPManager->getGlobalFrameAndNavTypeIndexOf(wp);
491 492 493 494 495
            // If not found, return (this should never happen, but helps safety)
            if (wpindex == -1) return;
            // Mark this wp as currently edited
            firingWaypointChange = wp;

496 497
            qDebug() << "UPDATING WAYPOINT" << wpindex << "IN 2D MAP";

498
            // Check if wp exists yet in map
lm's avatar
lm committed
499 500
            if (!waypointsToIcons.contains(wp))
            {
501
                // Create icon for new WP
502 503 504
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                Waypoint2DIcon* icon = new Waypoint2DIcon(map, this, wp, wpColor, wpindex);
505 506 507 508 509 510
                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
511 512 513 514 515 516 517 518 519 520
                // Add line element if this is NOT the first waypoint
                if (wpindex > 0)
                {
                    // Get predecessor of this WP
                    QVector<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
                    Waypoint* wp1 = wps.at(wpindex-1);
                    mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL);
                    // If we got a valid graphics item, continue
                    if (prevIcon)
                    {
521
                        mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, icon, wpColor, map);
lm's avatar
lm committed
522
                        line->setParentItem(map);
lm's avatar
lm committed
523 524 525 526
                        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                        if (group)
                        {
                            group->addToGroup(line);
lm's avatar
lm committed
527
                            group->setParentItem(map);
lm's avatar
lm committed
528 529 530
                        }
                    }
                }
lm's avatar
lm committed
531 532 533
            }
            else
            {
534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556
                // 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);
557
                }
558 559 560
                // Re-enable signals again
                this->blockSignals(false);
            }
561

562
            firingWaypointChange = NULL;
563

lm's avatar
lm committed
564 565 566
        }
        else
        {
567 568 569 570
            // 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
lm's avatar
lm committed
571 572
            if (waypointsToIcons.size() > currWPManager->getGlobalFrameAndNavTypeCount())
            {
573
                updateWaypointList(uas);
574 575
            }
        }
576
    }
577 578 579 580 581 582 583 584 585
}

/**
 * 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)
{
586
    qDebug() << "UPDATE WP LIST IN 2D MAP CALLED FOR UAS" << uas;
587 588
    // 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
589
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
lm's avatar
lm committed
590 591
    if ((uasInstance && (uasInstance->getWaypointManager() == currWPManager)) || uas == -1)
    {
592 593
        // ORDER MATTERS HERE!
        // TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
594

595 596
        qDebug() << "DELETING NOW OLD WPS";

597 598 599 600
        // Delete first all old waypoints
        // this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
        QVector<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
        foreach (Waypoint* wp, waypointsToIcons.keys())
601
        {
602 603
            if (!wps.contains(wp))
            {
lm's avatar
lm committed
604 605
                // Get icon to work on
                mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
606 607 608 609
                waypointsToIcons.remove(wp);
                iconsToWaypoints.remove(icon);
                WPDelete(icon);
            }
610 611
        }

612 613 614 615 616 617
        // Update all existing waypoints
        foreach (Waypoint* wp, waypointsToIcons.keys())
        {
            // Update remaining waypoints
            updateWaypoint(uas, wp);
        }
618

619 620 621
        // Update all potentially new waypoints
        foreach (Waypoint* wp, wps)
        {
622
            qDebug() << "UPDATING NEW WP" << wp->getId();
623 624 625
            // Update / add only if new
            if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
        }
lm's avatar
lm committed
626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646

        // Delete connecting waypoint lines
        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
        if (group)
        {
            foreach (QGraphicsItem* item, group->childItems())
            {
                delete item;
            }
        }

        // 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
647 648 649
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, currIcon, wpColor, map);
lm's avatar
lm committed
650
                line->setParentItem(map);
lm's avatar
lm committed
651 652 653 654
                QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                if (group)
                {
                    group->addToGroup(line);
lm's avatar
lm committed
655
                    group->setParentItem(map);
lm's avatar
lm committed
656 657 658 659
                }
            }
            prevIcon = currIcon;
        }
660
    }
lm's avatar
lm committed
661
}
662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704


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