QGCMapWidget.cc 28.1 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"
8
#include "ArduPilotMegaMAV.h"
lm's avatar
lm committed
9 10

QGCMapWidget::QGCMapWidget(QWidget *parent) :
11 12 13
    mapcontrol::OPMapWidget(parent),
    currWPManager(NULL),
    firingWaypointChange(NULL),
14
    maxUpdateInterval(2.1f), // 2 seconds
15 16 17
    followUAVEnabled(false),
    trailType(mapcontrol::UAVTrailType::ByTimeElapsed),
    trailInterval(2.0f),
18
    followUAVID(0),
19 20
    mapInitialized(false),
    homeAltitude(0)
lm's avatar
lm committed
21
{
22
    // Widget is inactive until shown
23
    defaultGuidedAlt = -1;
24
    loadSettings(false);
25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62

    this->setContextMenuPolicy(Qt::ActionsContextMenu);

}
void QGCMapWidget::guidedActionTriggered()
{
    if (currWPManager)
    {
        if (defaultGuidedAlt == -1)
        {
            if (!guidedAltActionTriggered())
            {
                return;
            }
        }
        // Create new waypoint and send it to the WPManager to send out.
        internals::PointLatLng pos = map->FromLocalToLatLng(mousePressPos.x(), mousePressPos.y());
        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()
{
    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;
}
63 64 65 66 67 68 69 70 71 72
void QGCMapWidget::cameraActionTriggered()
{
    ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas);
    if (newmav)
    {
        newmav->setMountConfigure(4,true,true,true);
        internals::PointLatLng pos = map->FromLocalToLatLng(mousePressPos.x(), mousePressPos.y());
        newmav->setMountControl(pos.Lat(),pos.Lng(),100,true);
    }
}
73 74 75 76 77 78 79 80 81 82

void QGCMapWidget::mousePressEvent(QMouseEvent *event)
{
    mapcontrol::OPMapWidget::mousePressEvent(event);
}

void QGCMapWidget::mouseReleaseEvent(QMouseEvent *event)
{
    mousePressPos = event->pos();
    mapcontrol::OPMapWidget::mouseReleaseEvent(event);
83 84 85 86 87 88
}

QGCMapWidget::~QGCMapWidget()
{
    SetShowHome(false);	// doing this appears to stop the map lib crashing on exit
    SetShowUAV(false);	//   "          "
89
    storeSettings();
90 91 92 93
}

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

97 98 99
    // Pass on to parent widget
    OPMapWidget::showEvent(event);

100 101
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)), Qt::UniqueConnection);
102 103
    connect(UASManager::instance(), SIGNAL(homePositionChanged(double,double,double)), this, SLOT(updateHomePosition(double,double,double)));

lm's avatar
lm committed
104 105 106 107
    foreach (UASInterface* uas, UASManager::instance()->getUASList())
    {
        addUAS(uas);
    }
lm's avatar
lm committed
108 109


110 111 112
    if (!mapInitialized)
    {
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(0, 0);
lm's avatar
lm committed
113

114 115
        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
116

117
        SetShowHome(true);					    // display the HOME position on the map
118 119
        Home->SetSafeArea(0);                         // set radius (meters)
        Home->SetShowSafeArea(false);                                         // show the safe area
120
        Home->SetCoord(pos_lat_lon);             // set the HOME position
lm's avatar
lm committed
121

122 123
        setFrameStyle(QFrame::NoFrame);      // no border frame
        setBackgroundBrush(QBrush(Qt::black)); // tile background
lm's avatar
lm committed
124

125 126
        // Set current home position
        updateHomePosition(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
127

128 129
        // Set currently selected system
        activeUASSet(UASManager::instance()->getActiveUAS());
130

131 132
        // Connect map updates to the adapter slots
        connect(this, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(handleMapWaypointEdit(WayPointItem*)));
133

134 135
        SetCurrentPosition(pos_lat_lon);         // set the map position
        setFocus();
136

137 138 139
        // Start timer
        connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateGlobalPosition()));
        mapInitialized = true;
140
        //QTimer::singleShot(800, this, SLOT(loadSettings()));
141
    }
142
    updateTimer.start(maxUpdateInterval*1000);
143
    // Update all UAV positions
144
    updateGlobalPosition();
lm's avatar
lm committed
145 146
}

147
void QGCMapWidget::hideEvent(QHideEvent* event)
lm's avatar
lm committed
148
{
149
    updateTimer.stop();
150 151
    storeSettings();
    OPMapWidget::hideEvent(event);
lm's avatar
lm committed
152
}
lm's avatar
lm committed
153

154 155 156 157
/**
 * @param changePosition Load also the last position from settings and update the map position.
 */
void QGCMapWidget::loadSettings(bool changePosition)
158 159 160 161 162 163 164 165
{
    // Atlantic Ocean near Africa, coordinate origin
    double lastZoom = 1;
    double lastLat = 0;
    double lastLon = 0;

    QSettings settings;
    settings.beginGroup("QGC_MAPWIDGET");
166 167 168 169 170 171 172 173
    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();
174 175
    settings.endGroup();

176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191
    // 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);
        }
    }

192 193 194
    // SET INITIAL POSITION AND ZOOM
    internals::PointLatLng pos_lat_lon = internals::PointLatLng(lastLat, lastLon);
    SetCurrentPosition(pos_lat_lon);        // set the map position
195
    SetZoom(lastZoom); // set map zoom level
196 197 198 199 200 201 202 203 204 205
}

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());
206 207
    settings.setValue("TRAIL_TYPE", static_cast<int>(trailType));
    settings.setValue("TRAIL_INTERVAL", trailInterval);
208 209 210 211 212 213
    settings.endGroup();
    settings.sync();
}

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

lm's avatar
lm committed
215
    // FIXME HACK!
lm's avatar
lm committed
216
    //if (currEditMode == EDIT_MODE_WAYPOINTS)
217 218 219 220 221
    {
        // If a waypoint manager is available
        if (currWPManager)
        {
            // Create new waypoint
lm's avatar
lm committed
222
            internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y());
223
            Waypoint* wp = currWPManager->createWaypoint();
224 225
            //            wp->blockSignals(true);
            //            wp->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
226 227
            wp->setLatitude(pos.Lat());
            wp->setLongitude(pos.Lng());
lm's avatar
lm committed
228
            wp->setAltitude(0);
229
            //            wp->blockSignals(false);
230
            //            currWPManager->notifyOfChangeEditable(wp);
231 232
        }
    }
lm's avatar
lm committed
233
    OPMapWidget::mouseDoubleClickEvent(event);
234 235 236
}


lm's avatar
lm committed
237 238
/**
 *
239
 * @param uas the UAS/MAV to monitor/display with the map widget
lm's avatar
lm committed
240 241 242 243
 */
void QGCMapWidget::addUAS(UASInterface* uas)
{
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
244
    connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)));
lm's avatar
lm committed
245 246
}

247 248 249
void QGCMapWidget::activeUASSet(UASInterface* uas)
{
    // Only execute if proper UAS is set
250
    if (!uas) return;
251
    this->uas = uas;
252 253

    // Disconnect old MAV manager
254 255
    if (currWPManager)
    {
256
        // Disconnect the waypoint manager / data storage from the UI
257 258 259 260
        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*)));
261 262
    }

263 264
    if (uas)
    {
265
        currWPManager = uas->getWaypointManager();
266 267 268 269 270 271
        QList<QAction*> actionList = this->actions();
        for (int i=0;i<actionList.size();i++)
        {
            this->removeAction(actionList[i]);
            actionList[i]->deleteLater();
        }
272 273 274 275 276 277 278 279 280 281
        if (currWPManager->guidedModeSupported())
        {
            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);
282 283 284 285 286 287 288 289

            if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
            {
                QAction *cameraaction = new QAction(this);
                cameraaction->setText("Point Camera Here");
                connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
                this->addAction(cameraaction);
            }
290
        }
291 292

        // Connect the waypoint manager / data storage to the UI
293 294 295 296
        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*)));
297

298
        updateSelectedSystem(uas->getUASID());
299
        followUAVID = uas->getUASID();
300 301 302

        // Delete all waypoints and add waypoint from new system
        updateWaypointList(uas->getUASID());
303 304 305
    }
}

lm's avatar
lm committed
306 307 308 309 310 311 312 313 314 315 316 317 318
/**
 * 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);

319 320
    // Immediate update
    if (maxUpdateInterval == 0)
321
    {
322 323 324 325 326 327 328 329 330
        // 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
331 332 333
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
334 335 336 337 338
        }

        // Set new lat/lon position of UAV icon
        internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
        uav->SetUAVPos(pos_lat_lon, alt);
339 340
        // Follow status
        if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
341 342
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((uas->getYaw()/M_PI)*180.0f);
343
    }
344
}
lm's avatar
lm committed
345

346 347 348 349 350 351 352 353 354 355 356 357 358 359
/**
 * 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);
360 361
            AddUAV(system->getUASID(), newUAV);
            uav = newUAV;
LM's avatar
LM committed
362 363 364
            uav->SetTrailTime(1);
            uav->SetTrailDistance(5);
            uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
365 366 367 368 369
        }

        // 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());
370 371
        // Follow status
        if (followUAVEnabled && system->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
372 373 374
        // Convert from radians to degrees and apply
        uav->SetUAVHeading((system->getYaw()/M_PI)*180.0f);
    }
375 376
}

377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406
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()
{
407
    updateLocalPosition();
408 409
}

410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425

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

/**
426
 * Does not update the system type or configuration, only the selected status
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441
 */
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));
        }
    }
}


442 443 444 445 446 447
// MAP NAVIGATION
void QGCMapWidget::showGoToDialog()
{
    bool ok;
    QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
                                         tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
448
                                         QString("%1,%2").arg(CurrentPosition().Lat(), 0, 'g', 6).arg(CurrentPosition().Lng(), 0, 'g', 6), &ok);
449 450
    if (ok && !text.isEmpty())
    {
451
        QStringList split = text.split(",");
452 453
        if (split.length() == 2)
        {
454 455 456 457 458 459
            bool convert;
            double latitude = split.first().toDouble(&convert);
            ok &= convert;
            double longitude = split.last().toDouble(&convert);
            ok &= convert;

460 461
            if (ok)
            {
462 463 464 465 466 467 468 469 470 471 472 473
                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);
474
    homeAltitude = altitude;
475 476 477
    SetShowHome(true);                      // display the HOME position on the map
}

478 479 480 481 482
void QGCMapWidget::goHome()
{
    SetCurrentPosition(Home->Coord());
}

483 484 485 486 487 488 489 490 491 492
/**
 * 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);
}

493 494 495 496 497 498 499 500 501 502 503 504 505 506
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();
    }
507 508 509 510 511 512
    else
    {
        RipMap();
        // Set empty area = unselect area
        map->SetSelectedArea(internals::RectLatLng());
    }
513 514
}

515

516 517 518 519 520 521 522
// 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
523
    if (firingWaypointChange == wp) return;
524 525
    // Not in cycle, block now from entering it
    firingWaypointChange = wp;
526
    // // qDebug() << "UPDATING WP FROM MAP";
527 528 529

    // Update WP values
    internals::PointLatLng pos = waypoint->Coord();
530 531 532

    // Block waypoint signals
    wp->blockSignals(true);
533 534
    wp->setLatitude(pos.Lat());
    wp->setLongitude(pos.Lng());
535 536 537
    // XXX Magic values
    wp->setAltitude(homeAltitude + 50.0f);
    wp->setAcceptanceRadius(10.0f);
538
    wp->blockSignals(false);
539

540

541 542
    internals::PointLatLng coord = waypoint->Coord();
    QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + "   " + QString::number(coord.Lng(), 'f', 6);
543
    // // qDebug() << "MAP WP COORD (MAP):" << coord_str << __FILE__ << __LINE__;
544
    QString wp_str = QString::number(wp->getLatitude(), 'f', 6) + "   " + QString::number(wp->getLongitude(), 'f', 6);
545
    // // qDebug() << "MAP WP COORD (WP):" << wp_str << __FILE__ << __LINE__;
546

547
    firingWaypointChange = NULL;
548 549

    emit waypointChanged(wp);
550
}
551 552

// WAYPOINT UPDATE FUNCTIONS
553 554

/**
555 556
 * This function is called if a a single waypoint is updated and
 * also if the whole list changes.
557
 */
558
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
559
{
560
    qDebug() << "UPDATING WP FUNCTION CALLED";
561 562
    // Source of the event was in this widget, do nothing
    if (firingWaypointChange == wp) return;
563 564
    // 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.
565
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
lm's avatar
lm committed
566 567
    if (uasInstance->getWaypointManager() == currWPManager || uas == -1)
    {
568
        // Only accept waypoints in global coordinate frame
lm's avatar
lm committed
569 570
        if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
        {
571 572 573 574 575
            // 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
576
            int wpindex = currWPManager->getGlobalFrameAndNavTypeIndexOf(wp);
577 578 579 580 581
            // If not found, return (this should never happen, but helps safety)
            if (wpindex == -1) return;
            // Mark this wp as currently edited
            firingWaypointChange = wp;

582 583
            qDebug() << "UPDATING WAYPOINT" << wpindex << "IN 2D MAP";

584
            // Check if wp exists yet in map
lm's avatar
lm committed
585 586
            if (!waypointsToIcons.contains(wp))
            {
587
                // Create icon for new WP
588 589 590
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                Waypoint2DIcon* icon = new Waypoint2DIcon(map, this, wp, wpColor, wpindex);
591 592 593 594 595 596
                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
597 598 599 600 601 602 603 604 605 606
                // 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)
                    {
607
                        mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, icon, wpColor, map);
lm's avatar
lm committed
608
                        line->setParentItem(map);
lm's avatar
lm committed
609 610 611 612
                        QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                        if (group)
                        {
                            group->addToGroup(line);
lm's avatar
lm committed
613
                            group->setParentItem(map);
lm's avatar
lm committed
614 615 616
                        }
                    }
                }
lm's avatar
lm committed
617 618 619
            }
            else
            {
620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642
                // 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);
643
                }
644 645 646
                // Re-enable signals again
                this->blockSignals(false);
            }
647

648
            firingWaypointChange = NULL;
649

lm's avatar
lm committed
650 651 652
        }
        else
        {
653 654 655 656
            // 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
657 658
            if (waypointsToIcons.size() > currWPManager->getGlobalFrameAndNavTypeCount())
            {
659
                updateWaypointList(uas);
660 661
            }
        }
662
    }
663 664 665 666 667 668 669 670 671
}

/**
 * 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)
{
672
    qDebug() << "UPDATE WP LIST IN 2D MAP CALLED FOR UAS" << uas;
673 674
    // 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
675
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
lm's avatar
lm committed
676 677
    if ((uasInstance && (uasInstance->getWaypointManager() == currWPManager)) || uas == -1)
    {
678 679
        // ORDER MATTERS HERE!
        // TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
680

681 682
        qDebug() << "DELETING NOW OLD WPS";

683 684 685 686
        // 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())
687
        {
688 689
            if (!wps.contains(wp))
            {
lm's avatar
lm committed
690 691
                // Get icon to work on
                mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
692 693 694 695
                waypointsToIcons.remove(wp);
                iconsToWaypoints.remove(icon);
                WPDelete(icon);
            }
696 697
        }

698 699 700 701 702 703
        // Update all existing waypoints
        foreach (Waypoint* wp, waypointsToIcons.keys())
        {
            // Update remaining waypoints
            updateWaypoint(uas, wp);
        }
704

705 706 707
        // Update all potentially new waypoints
        foreach (Waypoint* wp, wps)
        {
708
            qDebug() << "UPDATING NEW WP" << wp->getId();
709 710 711
            // Update / add only if new
            if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
        }
lm's avatar
lm committed
712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732

        // 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
733 734 735
                QColor wpColor(Qt::red);
                if (uasInstance) wpColor = uasInstance->getColor();
                mapcontrol::WaypointLineItem* line = new mapcontrol::WaypointLineItem(prevIcon, currIcon, wpColor, map);
lm's avatar
lm committed
736
                line->setParentItem(map);
lm's avatar
lm committed
737 738 739 740
                QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
                if (group)
                {
                    group->addToGroup(line);
lm's avatar
lm committed
741
                    group->setParentItem(map);
lm's avatar
lm committed
742 743 744 745
                }
            }
            prevIcon = currIcon;
        }
746
    }
lm's avatar
lm committed
747
}
748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790


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