QGCMapWidget.h 7.16 KB
Newer Older
lm's avatar
lm committed
1 2 3
#ifndef QGCMAPWIDGET_H
#define QGCMAPWIDGET_H

4
#include <QMap>
5
#include <QTimer>
Don Gagne's avatar
Don Gagne committed
6
#include "opmapcontrol.h"
lm's avatar
lm committed
7

8
// Choose one default map type
Lorenz Meier's avatar
Lorenz Meier committed
9 10
//#define MAP_DEFAULT_TYPE_BING
#define MAP_DEFAULT_TYPE_GOOGLE
11 12
//#define MAP_DEFAULT_TYPE_OSM

lm's avatar
lm committed
13
class UASInterface;
14 15
class UASWaypointManager;
class Waypoint;
16
typedef mapcontrol::WayPointItem WayPointItem;
lm's avatar
lm committed
17

18 19 20
/**
 * @brief Class representing a 2D map using aerial imagery
 */
lm's avatar
lm committed
21
class QGCMapWidget : public mapcontrol::OPMapWidget
lm's avatar
lm committed
22 23 24 25
{
    Q_OBJECT
public:
    explicit QGCMapWidget(QWidget *parent = 0);
lm's avatar
lm committed
26
    ~QGCMapWidget();
27 28 29 30
//    /** @brief Convert meters to pixels */
//    float metersToPixels(double meters);
//    double headingP1P2(internals::PointLatLng p1, internals::PointLatLng p2);
//    internals::PointLatLng targetLatLon(internals::PointLatLng source, double heading, double dist);
lm's avatar
lm committed
31

32 33
    /** @brief Map centered on current active system */
    bool getFollowUAVEnabled() { return followUAVEnabled; }
34
    /** @brief The maximum map update rate */
35 36 37 38 39
    float getUpdateRateLimit() { return maxUpdateInterval; }
    /** @brief Get the trail type */
    int getTrailType() { return static_cast<int>(trailType); }
    /** @brief Get the trail interval */
    float getTrailInterval() { return trailInterval; }
40

lm's avatar
lm committed
41
signals:
42
    void homePositionChanged(double latitude, double longitude, double altitude);
43 44 45
    /** @brief Signal for newly created map waypoints */
    void waypointCreated(Waypoint* wp);
    void waypointChanged(Waypoint* wp);
lm's avatar
lm committed
46 47

public slots:
48 49 50 51
    /** @brief Action triggered when guided action is selected from the context menu */
    void guidedActionTriggered();
    /** @brief Action triggered when guided action is selected from the context menu, allows for altitude selection */
    bool guidedAltActionTriggered();
52 53
    /** @brief Action triggered when set home action is selected from the context menu. */
    bool setHomeActionTriggered();
54
    /** @brief Add system to map view */
lm's avatar
lm committed
55
    void addUAS(UASInterface* uas);
56
    /** @brief Update the global position of a system */
57
    void updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec);
58 59
    /** @brief Update the global position of all systems */
    void updateGlobalPosition();
60 61 62 63
    /** @brief Update the local position and draw it converted to GPS reference */
    void updateLocalPosition();
    /** @brief Update the local position estimates (individual sensors) and draw it converted to GPS reference */
    void updateLocalPositionEstimates();
64 65
    /** @brief Update the type, size, etc. of this system */
    void updateSystemSpecs(int uas);
66 67 68 69
    /** @brief Change current system in focus / editing */
    void activeUASSet(UASInterface* uas);
    /** @brief Show a dialog to jump to given GPS coordinates */
    void showGoToDialog();
70 71
    /** @brief Jump to the home position on the map */
    void goHome();
72 73 74 75 76 77
    /** @brief Update this waypoint for this UAS */
    void updateWaypoint(int uas, Waypoint* wp);
    /** @brief Update the whole waypoint */
    void updateWaypointList(int uas);
    /** @brief Update the home position on the map */
    void updateHomePosition(double latitude, double longitude, double altitude);
78 79
    /** @brief Set update rate limit */
    void setUpdateRateLimit(float seconds);
80 81 82 83
    /** @brief Cache visible region to harddisk */
    void cacheVisibleRegion();
    /** @brief Set follow mode */
    void setFollowUAVEnabled(bool enabled) { followUAVEnabled = enabled; }
84
    /** @brief Set trail to time mode and set time @param seconds The minimum time between trail dots in seconds. If set to a value < 0, trails will be disabled*/
85 86 87 88
    void setTrailModeTimed(int seconds)
    {
        foreach(mapcontrol::UAVItem* uav, GetUAVS())
        {
89 90 91 92 93 94 95 96 97
            if (seconds >= 0)
            {
                uav->SetTrailTime(seconds);
                uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
            }
            else
            {
                uav->SetTrailType(mapcontrol::UAVTrailType::NoTrail);
            }
98 99
        }
    }
100
    /** @brief Set trail to distance mode and set time @param meters The minimum distance between trail dots in meters. The actual distance depends on the MAV's update rate as well. If set to a value < 0, trails will be disabled*/
101 102 103 104
    void setTrailModeDistance(int meters)
    {
        foreach(mapcontrol::UAVItem* uav, GetUAVS())
        {
105 106 107 108 109 110 111 112 113
            if (meters >= 0)
            {
                uav->SetTrailDistance(meters);
                uav->SetTrailType(mapcontrol::UAVTrailType::ByDistance);
            }
            else
            {
                uav->SetTrailType(mapcontrol::UAVTrailType::NoTrail);
            }
114 115
        }
    }
lm's avatar
lm committed
116 117 118 119 120 121 122 123
    /** @brief Delete all trails */
    void deleteTrails()
    {
        foreach(mapcontrol::UAVItem* uav, GetUAVS())
        {
            uav->DeleteTrail();
        }
    }
124

125 126 127 128 129
    void setZoomBlocked(bool blocked)
    {
        zoomBlocked = blocked;
    }

130
    /** @brief Load the settings for this widget from disk */
131
    void loadSettings(bool changePosition=true);
132
    /** @brief Store the settings for this widget to disk */
133 134
    void storeSettings();

135 136 137 138
protected slots:
    /** @brief Convert a map edit into a QGC waypoint event */
    void handleMapWaypointEdit(WayPointItem* waypoint);

139
protected:
140 141
    /** @brief Update the highlighting of the currently controlled system */
    void updateSelectedSystem(int uas);
142 143 144
    /** @brief Initialize */
    void showEvent(QShowEvent* event);
    void hideEvent(QHideEvent* event);
145
    void wheelEvent(QWheelEvent* event);
146 147
    void mousePressEvent(QMouseEvent *event);
    void mouseReleaseEvent(QMouseEvent *event);
148
    void mouseDoubleClickEvent(QMouseEvent* event);
149

150 151
    //void contextMenuEvent(QContextMenuEvent *);

152
    UASWaypointManager* currWPManager; ///< The current waypoint manager
153
    bool offlineMode;
154 155
    QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons;
    QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints;
156
    Waypoint* firingWaypointChange;
157 158
    QTimer updateTimer;
    float maxUpdateInterval;
159 160 161 162 163 164 165 166 167
    enum editMode {
        EDIT_MODE_NONE,
        EDIT_MODE_WAYPOINTS,
        EDIT_MODE_SWEEP,
        EDIT_MODE_UAVS,
        EDIT_MODE_HOME,
        EDIT_MODE_SAFE_AREA,
        EDIT_MODE_CACHING
    };
168
    editMode currEditMode;              ///< The current edit mode on the map
169
    bool followUAVEnabled;              ///< Does the map follow the UAV?
170 171
    mapcontrol::UAVTrailType::Types trailType; ///< Time or distance based trail dots
    float trailInterval;                ///< Time or distance between trail items
172
    int followUAVID;                    ///< Which UAV should be tracked?
173
    bool mapInitialized;                ///< Map initialized?
174
    bool mapPositionInitialized;        ///< The position on the map has a reasonable value?
175
    float homeAltitude;                 ///< Home altitude
176
    QPoint mousePressPos;               ///< Mouse position when the button is released.
177
    QPoint contextMousePressPos;        ///< Mouse position when context menu activated.
178
    int defaultGuidedAlt;               ///< Default altitude for guided mode
179
    bool zoomBlocked;                   ///< Wether zooming is blocked
180
    UASInterface *uas;                  ///< Currently selected UAS.
lm's avatar
lm committed
181 182 183 184

};

#endif // QGCMAPWIDGET_H