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

4
#include <QMap>
5
#include <QTimer>
6
#include "../../../libs/opmapcontrol/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
    /** @brief Action triggered with point-camera action is selected from the context menu */
    void cameraActionTriggered();
50 51 52 53
    /** @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();
54 55
    /** @brief Action triggered when set home action is selected from the context menu. */
    bool setHomeActionTriggered();
56
    /** @brief Add system to map view */
lm's avatar
lm committed
57
    void addUAS(UASInterface* uas);
58
    /** @brief Update the global position of a system */
lm's avatar
lm committed
59
    void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
60 61
    /** @brief Update the global position of all systems */
    void updateGlobalPosition();
62 63 64 65
    /** @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();
66 67
    /** @brief Update the type, size, etc. of this system */
    void updateSystemSpecs(int uas);
68 69 70 71
    /** @brief Change current system in focus / editing */
    void activeUASSet(UASInterface* uas);
    /** @brief Show a dialog to jump to given GPS coordinates */
    void showGoToDialog();
72 73
    /** @brief Jump to the home position on the map */
    void goHome();
74 75 76 77 78 79
    /** @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);
80 81
    /** @brief Set update rate limit */
    void setUpdateRateLimit(float seconds);
82 83 84 85
    /** @brief Cache visible region to harddisk */
    void cacheVisibleRegion();
    /** @brief Set follow mode */
    void setFollowUAVEnabled(bool enabled) { followUAVEnabled = enabled; }
86
    /** @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*/
87 88 89 90
    void setTrailModeTimed(int seconds)
    {
        foreach(mapcontrol::UAVItem* uav, GetUAVS())
        {
91 92 93 94 95 96 97 98 99
            if (seconds >= 0)
            {
                uav->SetTrailTime(seconds);
                uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
            }
            else
            {
                uav->SetTrailType(mapcontrol::UAVTrailType::NoTrail);
            }
100 101
        }
    }
102
    /** @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*/
103 104 105 106
    void setTrailModeDistance(int meters)
    {
        foreach(mapcontrol::UAVItem* uav, GetUAVS())
        {
107 108 109 110 111 112 113 114 115
            if (meters >= 0)
            {
                uav->SetTrailDistance(meters);
                uav->SetTrailType(mapcontrol::UAVTrailType::ByDistance);
            }
            else
            {
                uav->SetTrailType(mapcontrol::UAVTrailType::NoTrail);
            }
116 117
        }
    }
lm's avatar
lm committed
118 119 120 121 122 123 124 125
    /** @brief Delete all trails */
    void deleteTrails()
    {
        foreach(mapcontrol::UAVItem* uav, GetUAVS())
        {
            uav->DeleteTrail();
        }
    }
126

127 128 129 130 131
    void setZoomBlocked(bool blocked)
    {
        zoomBlocked = blocked;
    }

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

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

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

152 153
    //void contextMenuEvent(QContextMenuEvent *);

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

};

#endif // QGCMAPWIDGET_H