QGCMapWidget.cc 8.96 KB
Newer Older
lm's avatar
lm committed
1
#include "QGCMapWidget.h"
lm's avatar
lm committed
2
#include "UASInterface.h"
lm's avatar
lm committed
3
#include "UASManager.h"
4
#include "MAV2DIcon.h"
lm's avatar
lm committed
5 6

QGCMapWidget::QGCMapWidget(QWidget *parent) :
lm's avatar
lm committed
7
        mapcontrol::OPMapWidget(parent)
lm's avatar
lm committed
8
{
lm's avatar
lm committed
9
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
10
    connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(updateSelectedSystem(int)));
lm's avatar
lm committed
11 12 13 14
    foreach (UASInterface* uas, UASManager::instance()->getUASList())
    {
        addUAS(uas);
    }
lm's avatar
lm committed
15 16 17 18 19 20




    internals::PointLatLng pos_lat_lon = internals::PointLatLng(0, 0);

lm's avatar
lm committed
21 22
    //        // **************
    //        // default home position
lm's avatar
lm committed
23

lm's avatar
lm committed
24 25 26
    //        home_position.coord = pos_lat_lon;
    //        home_position.altitude = altitude;
    //        home_position.locked = false;
lm's avatar
lm committed
27

lm's avatar
lm committed
28 29
    //        // **************
    //        // default magic waypoint params
lm's avatar
lm committed
30

lm's avatar
lm committed
31 32 33 34 35 36 37
    //        magic_waypoint.map_wp_item = NULL;
    //        magic_waypoint.coord = home_position.coord;
    //        magic_waypoint.altitude = altitude;
    //        magic_waypoint.description = "Magic waypoint";
    //        magic_waypoint.locked = false;
    //        magic_waypoint.time_seconds = 0;
    //        magic_waypoint.hold_time_seconds = 0;
lm's avatar
lm committed
38

lm's avatar
lm committed
39
    const int safe_area_radius_list[] = {5, 10, 20, 50, 100, 200, 500, 1000, 2000, 5000};   // meters
lm's avatar
lm committed
40

lm's avatar
lm committed
41
    const int uav_trail_time_list[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10};                      // seconds
lm's avatar
lm committed
42

lm's avatar
lm committed
43
    const int uav_trail_distance_list[] = {1, 2, 5, 10, 20, 50, 100, 200, 500};             // meters
lm's avatar
lm committed
44

lm's avatar
lm committed
45 46
    SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter);	    // set how the mouse wheel zoom functions
    SetFollowMouse(true);				    // we want a contiuous mouse position reading
lm's avatar
lm committed
47

lm's avatar
lm committed
48 49
    SetShowHome(true);					    // display the HOME position on the map
    SetShowUAV(true);					    // display the UAV position on the map
lm's avatar
lm committed
50

lm's avatar
lm committed
51 52
    Home->SetSafeArea(safe_area_radius_list[0]);                         // set radius (meters)
    Home->SetShowSafeArea(true);                                         // show the safe area
lm's avatar
lm committed
53

lm's avatar
lm committed
54 55
    UAV->SetTrailTime(uav_trail_time_list[0]);                           // seconds
    UAV->SetTrailDistance(uav_trail_distance_list[1]);                   // meters
lm's avatar
lm committed
56

57
    // UAV->SetTrailType(UAVTrailType::ByTimeElapsed);
lm's avatar
lm committed
58 59
    //  UAV->SetTrailType(UAVTrailType::ByDistance);

lm's avatar
lm committed
60 61
    GPS->SetTrailTime(uav_trail_time_list[0]);                           // seconds
    GPS->SetTrailDistance(uav_trail_distance_list[1]);                   // meters
lm's avatar
lm committed
62

63
    // GPS->SetTrailType(UAVTrailType::ByTimeElapsed);
lm's avatar
lm committed
64

lm's avatar
lm committed
65 66 67 68 69 70 71 72 73 74 75 76 77 78 79
    SetCurrentPosition(pos_lat_lon);         // set the map position
    Home->SetCoord(pos_lat_lon);             // set the HOME position
    UAV->SetUAVPos(pos_lat_lon, 0.0);        // set the UAV position
    GPS->SetUAVPos(pos_lat_lon, 0.0);        // set the UAV position

    setFrameStyle(QFrame::NoFrame);      // no border frame
    setBackgroundBrush(QBrush(Qt::black)); // tile background

    setFocus();
}

QGCMapWidget::~QGCMapWidget()
{
    SetShowHome(false);	// doing this appears to stop the map lib crashing on exit
    SetShowUAV(false);	//   "          "
lm's avatar
lm committed
80
}
lm's avatar
lm committed
81 82 83 84 85 86 87

/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void QGCMapWidget::addUAS(UASInterface* uas)
{
88
    qDebug() << "ADDING UAS";
lm's avatar
lm committed
89 90
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
    //connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
91
    connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)));
lm's avatar
lm committed
92 93 94 95 96 97 98 99 100 101 102 103 104 105 106
}

/**
 * Updates the global position of one MAV and append the last movement to the trail
 *
 * @param uas The unmanned air system
 * @param lat Latitude in WGS84 ellipsoid
 * @param lon Longitutde in WGS84 ellipsoid
 * @param alt Altitude over mean sea level
 * @param usec Timestamp of the position message in milliseconds FIXME will move to microseconds
 */
void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
    Q_UNUSED(usec);

107 108 109 110
    // Get reference to graphic UAV item
    mapcontrol::UAVItem* uav = GetUAV(uas->getUASID());
    // Check if reference is valid, else create a new one
    if (uav == NULL)
111
    {
112 113 114
        MAV2DIcon* newUAV = new MAV2DIcon(map, this, uas);
        newUAV->setParentItem(map);
        UAVS.insert(uas->getUASID(), newUAV);
115
        uav = GetUAV(uas->getUASID());
116
    }
lm's avatar
lm committed
117

118 119 120
    // Set new lat/lon position of UAV icon
    internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
    uav->SetUAVPos(pos_lat_lon, alt);
121
    uav->SetUAVHeading((uas->getYaw()/M_PI)*180.0f);
122 123 124 125 126 127 128 129 130 131

//    static int uasid = 220;
//    if (uas->getUASID() == uasid)
//    {
//        internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
//        UAV->SetUAVPos(pos_lat_lon, alt);
//        if (!UAV->isVisible()) UAV->show();
//        qDebug() << "Updating 2D map position" << uas->getUASID() << "LAT:" << lat << "LON:" << lon;
//    }

lm's avatar
lm committed
132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189
//        QPointF coordinate;
//        coordinate.setX(lon);
//        coordinate.setY(lat);



//        if (!uasIcons.contains(uas->getUASID())) {
//            // Get the UAS color
//            QColor uasColor = uas->getColor();

//            // Icon
//            //QPen* pointpen = new QPen(uasColor);
//            qDebug() << "2D MAP: ADDING" << uas->getUASName() << __FILE__ << __LINE__;
//            p = new MAV2DIcon(uas, 68, uas->getSystemType(), uas->getColor(), QString("%1").arg(uas->getUASID()), qmapcontrol::Point::Middle);
//            uasIcons.insert(uas->getUASID(), p);
//            mc->layer("Waypoints")->addGeometry(p);

//            // Line
//            // A QPen also can use transparency

//            //        QList<qmapcontrol::Point*> points;
//            //        points.append(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
//            //        QPen* linepen = new QPen(uasColor.darker());
//            //        linepen->setWidth(2);

//            //        // Create tracking line string
//            //        qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, QString("%1").arg(uas->getUASID()), linepen);
//            //        uasTrails.insert(uas->getUASID(), ls);

//            //        // Add the LineString to the layer
//            //        mc->layer("Waypoints")->addGeometry(ls);
//        } else {
//            //        p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
//            //        if (p)
//            //        {
//            p = uasIcons.value(uas->getUASID());
//            p->setCoordinate(QPointF(lon, lat));
//            //p->setYaw(uas->getYaw());
//            //        }
//            // Extend trail
//            //        uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
//        }

//        if (isVisible()) mc->updateRequest(p->boundingBox().toRect());

//        //if (isVisible()) mc->updateRequestNew();//(uasTrails.value(uas->getUASID())->boundingBox().toRect());

//        if (this->mav && uas->getUASID() == this->mav->getUASID()) {
//            // Limit the position update rate
//            quint64 currTime = MG::TIME::getGroundTimeNow();
//            if (currTime - lastUpdate > 120) {
//                lastUpdate = currTime;
//                // Sets the view to the interesting area
//                if (followgps->isChecked()) {
//                    updatePosition(0, lon, lat);
//                } else {
//                    // Refresh the screen
//                    //if (isVisible()) mc->updateRequestNew();
190 191 192 193 194 195 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
    //                }
    //            }
    //        }
}


void QGCMapWidget::updateSystemSpecs(int uas)
{
    foreach (mapcontrol::UAVItem* p, UAVS.values())
    {
        MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
        if (icon && icon->getUASId() == uas)
        {
            // Set new airframe
            icon->setAirframe(UASManager::instance()->getUASForId(uas)->getAirframe());
            icon->drawIcon();
        }
    }
}

/**
 * Does not update the system type or configuration, only the current state.
 */
void QGCMapWidget::updateSelectedSystem(int uas)
{
    foreach (mapcontrol::UAVItem* p, UAVS.values())
    {
        MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
        if (icon)
        {
            // Set as selected if ids match
            icon->setSelectedUAS((icon->getUASId() == uas));
        }
    }
}

///**
// * Updates all UAVs at once
// */
//void QGCMapWidget::updateUAVs()
//{

//}

/**
 * Updates the attitude
 */
void QGCMapWidget::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec)
{
//    Q_UNUSED(roll);
//    Q_UNUSED(pitch);
//    Q_UNUSED(usec);
//    if (mc) {

//        if (uas) {
//            MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID(), NULL));
//            if (icon) {
//                icon->setYaw(yaw);
lm's avatar
lm committed
248 249
//            }
//        }
250
//    }
lm's avatar
lm committed
251
}