diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index ca57341489548e28b631d63782ef54fe1e53f1dd..90469270ea5679a72b0fa593d4d8942f6e1cbcca 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -47,7 +47,7 @@ UASWaypointManager::UASWaypointManager(UAS* _uas) current_state(WP_IDLE), current_partner_systemid(0), current_partner_compid(0), - currentWaypointEditable(NULL), + currentWaypointEditable(), protocol_timer(this) { @@ -113,7 +113,7 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, { Q_UNUSED(mav); Q_UNUSED(time); - if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU)) + if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU)) { double xdiff = x-currentWaypointEditable->getX(); double ydiff = y-currentWaypointEditable->getY(); @@ -131,7 +131,7 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l Q_UNUSED(altWGS84); Q_UNUSED(lon); Q_UNUSED(lat); - if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) + if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) { // TODO FIXME Calculate distance double dist = 0; diff --git a/src/uas/UASWaypointManager.h b/src/uas/UASWaypointManager.h index 4dda426b1f74cfc97008a3176d13fa8015811849..b6179596f2d381cd2009cd0aeb80f2dbce6450f3 100644 --- a/src/uas/UASWaypointManager.h +++ b/src/uas/UASWaypointManager.h @@ -35,6 +35,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include #include "Waypoint.h" #include "QGCMAVLink.h" class UAS; @@ -180,7 +181,7 @@ private: QList waypointsViewOnly; ///< local copy of current waypoint list on MAV QList waypointsEditable; ///< local editable waypoint list - Waypoint* currentWaypointEditable; ///< The currently used waypoint + QPointer currentWaypointEditable; ///< The currently used waypoint QList waypoint_buffer; ///< buffer for waypoints during communication QTimer protocol_timer; ///< Timer to catch timeouts bool standalone; ///< If standalone is set, do not write to UAS