Browse Source

Merge pull request #1119 from mavlink/ptr_fix

Ptr fix - fixes #1117
QGC4.4
Don Gagne 11 years ago
parent
commit
277c161874
  1. 6
      src/uas/UASWaypointManager.cc
  2. 3
      src/uas/UASWaypointManager.h
  3. 35
      src/ui/map/Waypoint2DIcon.cc
  4. 2
      src/ui/map/Waypoint2DIcon.h

6
src/uas/UASWaypointManager.cc

@ -47,7 +47,7 @@ UASWaypointManager::UASWaypointManager(UAS* _uas)
current_state(WP_IDLE), current_state(WP_IDLE),
current_partner_systemid(0), current_partner_systemid(0),
current_partner_compid(0), current_partner_compid(0),
currentWaypointEditable(NULL), currentWaypointEditable(),
protocol_timer(this) protocol_timer(this)
{ {
@ -113,7 +113,7 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x,
{ {
Q_UNUSED(mav); Q_UNUSED(mav);
Q_UNUSED(time); 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 xdiff = x-currentWaypointEditable->getX();
double ydiff = y-currentWaypointEditable->getY(); double ydiff = y-currentWaypointEditable->getY();
@ -131,7 +131,7 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l
Q_UNUSED(altWGS84); Q_UNUSED(altWGS84);
Q_UNUSED(lon); Q_UNUSED(lon);
Q_UNUSED(lat); 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 // TODO FIXME Calculate distance
double dist = 0; double dist = 0;

3
src/uas/UASWaypointManager.h

@ -35,6 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include <QObject> #include <QObject>
#include <QList> #include <QList>
#include <QTimer> #include <QTimer>
#include <QPointer>
#include "Waypoint.h" #include "Waypoint.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
class UAS; class UAS;
@ -180,7 +181,7 @@ private:
QList<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV QList<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QList<Waypoint *> waypointsEditable; ///< local editable waypoint list 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 QList<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication
QTimer protocol_timer; ///< Timer to catch timeouts QTimer protocol_timer; ///< Timer to catch timeouts
bool standalone; ///< If standalone is set, do not write to UAS bool standalone; ///< If standalone is set, do not write to UAS

35
src/ui/map/Waypoint2DIcon.cc

@ -6,7 +6,7 @@
Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, qreal latitude, qreal longitude, qreal altitude, int listindex, QString name, QString description, int radius) Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, qreal latitude, qreal longitude, qreal altitude, int listindex, QString name, QString description, int radius)
: mapcontrol::WayPointItem(internals::PointLatLng(latitude, longitude), altitude, description, map), : mapcontrol::WayPointItem(internals::PointLatLng(latitude, longitude), altitude, description, map),
parent(parent), parent(parent),
waypoint(NULL), waypoint(),
radius(radius), radius(radius),
showAcceptanceRadius(true), showAcceptanceRadius(true),
showOrbit(false), showOrbit(false),
@ -55,7 +55,7 @@ void Waypoint2DIcon::SetHeading(float heading)
void Waypoint2DIcon::updateWaypoint() void Waypoint2DIcon::updateWaypoint()
{ {
if (waypoint) { if (!waypoint.isNull()) {
// Store old size // Store old size
static QRectF oldSize; static QRectF oldSize;
@ -97,13 +97,16 @@ QRectF Waypoint2DIcon::boundingRect() const
int loiter = 0; int loiter = 0;
int acceptance = 0; int acceptance = 0;
internals::PointLatLng coord = (internals::PointLatLng)Coord(); internals::PointLatLng coord = (internals::PointLatLng)Coord();
if (waypoint && showAcceptanceRadius && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT))
{ if (!waypoint.isNull()) {
acceptance = map->metersToPixels(waypoint->getAcceptanceRadius(), coord); if (showAcceptanceRadius && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT))
} {
if (waypoint && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS))) acceptance = map->metersToPixels(waypoint->getAcceptanceRadius(), coord);
{ }
loiter = map->metersToPixels(waypoint->getLoiterOrbit(), coord); if (((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS)))
{
loiter = map->metersToPixels(waypoint->getLoiterOrbit(), coord);
}
} }
int width = qMax(picture.width()/2, qMax(loiter, acceptance)); int width = qMax(picture.width()/2, qMax(loiter, acceptance));
@ -156,7 +159,7 @@ void Waypoint2DIcon::drawIcon()
// If this is not a waypoint (only the default representation) // If this is not a waypoint (only the default representation)
// or it is a waypoint, but not one where direction has no meaning // or it is a waypoint, but not one where direction has no meaning
// then draw the heading indicator // then draw the heading indicator
if (!waypoint || (waypoint && ( if (waypoint.isNull() || (waypoint && (
(waypoint->getAction() != (int)MAV_CMD_NAV_TAKEOFF) && (waypoint->getAction() != (int)MAV_CMD_NAV_TAKEOFF) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_LAND) && (waypoint->getAction() != (int)MAV_CMD_NAV_LAND) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_UNLIM) && (waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_UNLIM) &&
@ -171,7 +174,7 @@ void Waypoint2DIcon::drawIcon()
painter.drawLine(p.x(), p.y(), p.x()+sin(Heading()/180.0f*M_PI) * rad, p.y()-cos(Heading()/180.0f*M_PI) * rad); painter.drawLine(p.x(), p.y(), p.x()+sin(Heading()/180.0f*M_PI) * rad, p.y()-cos(Heading()/180.0f*M_PI) * rad);
} }
if ((waypoint != NULL) && (waypoint->getAction() == (int)MAV_CMD_NAV_TAKEOFF)) if (((!waypoint.isNull())) && (waypoint->getAction() == (int)MAV_CMD_NAV_TAKEOFF))
{ {
// Takeoff waypoint // Takeoff waypoint
int width = picture.width()-penWidth; int width = picture.width()-penWidth;
@ -187,7 +190,7 @@ void Waypoint2DIcon::drawIcon()
painter.setPen(pen2); painter.setPen(pen2);
painter.drawRect(width*0.3, height*0.3f, width*0.6f, height*0.6f); painter.drawRect(width*0.3, height*0.3f, width*0.6f, height*0.6f);
} }
else if ((waypoint != NULL) && (waypoint->getAction() == (int)MAV_CMD_NAV_LAND)) else if (((!waypoint.isNull())) && (waypoint->getAction() == (int)MAV_CMD_NAV_LAND))
{ {
// Landing waypoint // Landing waypoint
int width = (picture.width())/2-penWidth; int width = (picture.width())/2-penWidth;
@ -199,7 +202,7 @@ void Waypoint2DIcon::drawIcon()
painter.drawEllipse(p, width, height); painter.drawEllipse(p, width, height);
painter.drawLine(p.x()-width/2, p.y()-height/2, 2*width, 2*height); painter.drawLine(p.x()-width/2, p.y()-height/2, 2*width, 2*height);
} }
else if ((waypoint != NULL) && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS))) else if (((!waypoint.isNull())) && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS)))
{ {
// Loiter waypoint // Loiter waypoint
int width = (picture.width()-penWidth)/2; int width = (picture.width()-penWidth)/2;
@ -211,7 +214,7 @@ void Waypoint2DIcon::drawIcon()
painter.drawEllipse(p, width, height); painter.drawEllipse(p, width, height);
painter.drawPoint(p); painter.drawPoint(p);
} }
else if ((waypoint != NULL) && (waypoint->getAction() == (int)MAV_CMD_NAV_RETURN_TO_LAUNCH)) else if (((!waypoint.isNull())) && (waypoint->getAction() == (int)MAV_CMD_NAV_RETURN_TO_LAUNCH))
{ {
// Return to launch waypoint // Return to launch waypoint
int width = picture.width()-penWidth; int width = picture.width()-penWidth;
@ -284,7 +287,7 @@ void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *op
penBlack.setWidth(4); penBlack.setWidth(4);
pen.setColor(color); pen.setColor(color);
if ((waypoint) && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT) && showAcceptanceRadius) if ((!waypoint.isNull()) && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT) && showAcceptanceRadius)
{ {
QPen redPen = QPen(pen); QPen redPen = QPen(pen);
redPen.setColor(Qt::yellow); redPen.setColor(Qt::yellow);
@ -298,7 +301,7 @@ void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *op
painter->drawEllipse(QPointF(0, 0), acceptance, acceptance); painter->drawEllipse(QPointF(0, 0), acceptance, acceptance);
} }
} }
if ((waypoint) && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS))) if ((!waypoint.isNull()) && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS)))
{ {
QPen penDash(color); QPen penDash(color);
penDash.setWidth(1); penDash.setWidth(1);

2
src/ui/map/Waypoint2DIcon.h

@ -42,7 +42,7 @@ public:
protected: protected:
mapcontrol::OPMapWidget* parent; ///< Parent widget mapcontrol::OPMapWidget* parent; ///< Parent widget
Waypoint* waypoint; ///< Waypoint data container this icon represents QPointer<Waypoint> waypoint; ///< Waypoint data container this icon represents
int radius; ///< Radius / diameter of the icon in pixels int radius; ///< Radius / diameter of the icon in pixels
bool showAcceptanceRadius; bool showAcceptanceRadius;
bool showOrbit; bool showOrbit;

Loading…
Cancel
Save