Waypoint2DIcon.cc 8.66 KB
Newer Older
1 2
#include "Waypoint2DIcon.h"
#include <QPainter>
3
#include "opmapcontrol.h"
4

5 6 7 8 9 10 11 12
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),
    parent(parent),
    waypoint(NULL),
    radius(radius),
    showAcceptanceRadius(true),
    showOrbit(false),
    color(Qt::red)
13
{
14 15 16 17 18 19 20
    SetHeading(0);
    SetNumber(listindex);
    if (mypen == NULL) mypen = new QPen(Qt::red);
//    drawIcon(mypen);
    this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
    picture = QPixmap(radius+1, radius+1);
    drawIcon();
21 22
}

23 24 25 26 27 28 29 30
Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, Waypoint* wp, const QColor& color, int listindex, int radius)
    : mapcontrol::WayPointItem(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()), wp->getAltitude(), wp->getDescription(), map),
    parent(parent),
    waypoint(wp),
    radius(radius),
    showAcceptanceRadius(true),
    showOrbit(false),
    color(color)
31
{
32 33 34 35 36 37
    SetHeading(wp->getYaw());
    SetNumber(listindex);
    if (mypen == NULL) mypen = new QPen(Qt::red);
//    drawIcon(mypen);
    this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
    picture = QPixmap(radius+1, radius+1);
38
    updateWaypoint();
39 40
}

41
Waypoint2DIcon::~Waypoint2DIcon()
42
{
43
    delete &picture;
44 45 46 47 48
}

void Waypoint2DIcon::setPen(QPen* pen)
{
    mypen = pen;
49
//    drawIcon(pen);
50 51
}

52
void Waypoint2DIcon::SetHeading(float heading)
53
{
54 55
    mapcontrol::WayPointItem::SetHeading(heading);
    drawIcon();
56 57
}

58 59
void Waypoint2DIcon::updateWaypoint()
{
60
    if (waypoint) {
61 62 63
        // Store old size
        static QRectF oldSize;

64 65
        SetHeading(waypoint->getYaw());
        SetCoord(internals::PointLatLng(waypoint->getLatitude(), waypoint->getLongitude()));
66 67 68

        qDebug() << "UPDATING WP:" << waypoint->getId() << "LAT:" << waypoint->getLatitude() << "LON:" << waypoint->getLongitude();

69 70 71 72
        SetDescription(waypoint->getDescription());
        SetAltitude(waypoint->getAltitude());
        // FIXME Add SetNumber (currently needs a separate call)
        drawIcon();
73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93
        QRectF newSize = boundingRect();

        qDebug() << "WIDTH" << newSize.width() << "<" << oldSize.width();

        // If new size is smaller than old size, update surrounding
        if ((newSize.width() <= oldSize.width()) || (newSize.height() <= oldSize.height()))
        {
            // If the symbol size was reduced, enforce an update of the environment
//            update(oldSize);
            int oldWidth = oldSize.width() + 20;
            int oldHeight = oldSize.height() + 20;
            map->update(this->x()-10, this->y()-10, oldWidth, oldHeight);
            qDebug() << "UPDATING DUE TO SMALLER SIZE";
            qDebug() << "X:" << this->x()-1 << "Y:" << this->y()-1 << "WIDTH:" << oldWidth << "HEIGHT:" << oldHeight;
        }
        else
        {
            // Symbol size stayed constant or increased, use new size for update
            this->update();
        }
        oldSize = boundingRect();
94 95 96 97 98 99 100 101 102 103 104 105
        qDebug() << "UPDATING WP";
    }
}

QRectF Waypoint2DIcon::boundingRect() const
{
    int loiter = 0;
    int acceptance = 0;
    internals::PointLatLng coord = (internals::PointLatLng)Coord();
    if (waypoint && showAcceptanceRadius && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT))
    {
        acceptance = map->metersToPixels(waypoint->getAcceptanceRadius(), coord);
106
    }
107 108 109 110 111 112 113 114 115
    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)))
    {
        loiter = map->metersToPixels(waypoint->getLoiterOrbit(), coord);
    }

    int width = qMax(picture.width()/2, qMax(loiter, acceptance));
    int height = qMax(picture.height()/2, qMax(loiter, acceptance));

    return QRectF(-width,-height,2*width,2*height);
116 117
}

118 119 120 121 122 123 124 125 126 127 128 129 130 131
void Waypoint2DIcon::SetReached(const bool &value)
{
    // DO NOTHING
    Q_UNUSED(value);
//    reached=value;
//    emit WPValuesChanged(this);
//    if(value)
//        picture.load(QString::fromUtf8(":/markers/images/bigMarkerGreen.png"));
//    else
//        picture.load(QString::fromUtf8(":/markers/images/marker.png"));
//    this->update();

}

132
void Waypoint2DIcon::drawIcon()
133
{
134 135
    picture.fill(Qt::transparent);
    QPainter painter(&picture);
136 137

    // DRAW WAYPOINT
138
    QPointF p(picture.width()/2, picture.height()/2);
139 140 141

    QPolygonF poly(4);
    // Top point
142
    poly.replace(0, QPointF(p.x(), p.y()-picture.height()/2.0f));
143
    // Right point
144
    poly.replace(1, QPointF(p.x()+picture.width()/2.0f, p.y()));
145
    // Bottom point
146 147
    poly.replace(2, QPointF(p.x(), p.y() + picture.height()/2.0f));
    poly.replace(3, QPointF(p.x() - picture.width()/2.0f, p.y()));
148 149 150 151 152 153 154 155 156 157 158 159 160 161

//    // Select color based on if this is the current waypoint
//    if (list.at(i)->getCurrent())
//    {
//        color = QGC::colorCyan;//uas->getColor();
//        pen.setWidthF(refLineWidthToPen(0.8f));
//    }
//    else
//    {
//        color = uas->getColor();
//        pen.setWidthF(refLineWidthToPen(0.4f));
//    }

    //pen.setColor(color);
162 163 164 165 166
//    if (pen) {
//        pen->setWidthF(2);
//        painter.setPen(*pen);
//    } else {
        QPen pen2(color);
167 168
        pen2.setWidth(2);
        painter.setPen(pen2);
169
//    }
170 171
    painter.setBrush(Qt::NoBrush);

172
    int waypointSize = qMin(picture.width(), picture.height());
173
    float rad = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
174 175 176 177 178 179 180 181

    // If this is not a waypoint (only the default representation)
    // or it is a waypoint, but not one where direction has no meaning
    // then draw the heading indicator
    if (!waypoint || (waypoint && (
            (waypoint->getAction() != (int)MAV_CMD_NAV_TAKEOFF) &&
            (waypoint->getAction() != (int)MAV_CMD_NAV_LAND) &&
            (waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_UNLIM) &&
182 183
            (waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_TIME) &&
            (waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_TURNS)
184 185 186 187 188 189 190 191 192 193
            )))
    {
        painter.drawLine(p.x(), p.y(), p.x()+sin(Heading()) * rad, p.y()-cos(Heading()) * rad);
    }

    if ((waypoint != NULL) && (waypoint->getAction() == (int)MAV_CMD_NAV_TAKEOFF))
    {
        // Takeoff waypoint
        int width = (picture.width()-1);
        int height = (picture.height()-1);
194 195
        painter.drawRect(0, 0, width, height);
        painter.drawRect(width*0.2, height*0.2f, width*0.6f, height*0.6f);
196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248
    }
    else if ((waypoint != NULL) && (waypoint->getAction() == (int)MAV_CMD_NAV_LAND))
    {
        // Landing waypoint
        int width = (picture.width()-1)/2;
        int height = (picture.height()-1)/2;
        painter.drawEllipse(p, width, height);
        painter.drawEllipse(p, width*0.6f, height*0.6f);
        painter.drawLine(0, 0, picture.width(), picture.height());
        painter.drawLine(picture.width(), 0, 0, picture.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)))
    {
        // Loiter waypoint
        int width = (picture.width()-1)/2;
        int height = (picture.height()-1)/2;
        painter.drawEllipse(p, width, height);
    }
    else
    {
        // Navigation waypoint
        painter.drawPolygon(poly);
    }
}

void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
{
    Q_UNUSED(option);
    Q_UNUSED(widget);
    painter->drawPixmap(-picture.width()/2,-picture.height()/2,picture);
    if (this->isSelected())
    {
        painter->drawRect(QRectF(-picture.width()/2,-picture.height()/2,picture.width()-1,picture.height()-1));
    }

    QPen pen = painter->pen();
    pen.setColor(color);

    if ((waypoint) && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT) && showAcceptanceRadius)
    {
        QPen redPen = QPen(pen);
        redPen.setColor(Qt::red);
        painter->setPen(redPen);
        const int acceptance = map->metersToPixels(waypoint->getAcceptanceRadius(), Coord());
        if (waypoint) 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)))
    {
        painter->setPen(pen);
        pen.setWidth(2);
        const int loiter = map->metersToPixels(waypoint->getLoiterOrbit(), Coord());
        if (waypoint) painter->drawEllipse(QPointF(0, 0), loiter, loiter);
    }
249
}