Commit 58c70778 authored by Lorenz Meier's avatar Lorenz Meier

UASWaypointManager: protect against possible null pointer. Fixes #1117

parent 0f4a168f
......@@ -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;
......
......@@ -35,6 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include <QObject>
#include <QList>
#include <QTimer>
#include <QPointer>
#include "Waypoint.h"
#include "QGCMAVLink.h"
class UAS;
......@@ -180,7 +181,7 @@ private:
QList<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QList<Waypoint *> waypointsEditable; ///< local editable waypoint list
Waypoint* currentWaypointEditable; ///< The currently used waypoint
QPointer<Waypoint> currentWaypointEditable; ///< The currently used waypoint
QList<mavlink_mission_item_t *> 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
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment