diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index d0c95be23ffc6d1a45c14d276383d140d5089bde..67582631c296814ce9466222ab74647055ad6ee2 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -303,9 +303,6 @@ void QGCMapWidget::updateLocalPosition() } // Set new lat/lon position of UAV icon - double latitude = UASManager::instance()->getHomeLatitude(); - double longitude = UASManager::instance()->getHomeLongitude(); - double altitude = UASManager::instance()->getHomeAltitude(); internals::PointLatLng pos_lat_lon = internals::PointLatLng(system->getLatitude(), system->getLongitude()); uav->SetUAVPos(pos_lat_lon, system->getAltitude()); // Follow status @@ -317,33 +314,7 @@ void QGCMapWidget::updateLocalPosition() void QGCMapWidget::updateLocalPositionEstimates() { - QList systems = UASManager::instance()->getUASList(); - foreach (UASInterface* system, systems) - { - // Get reference to graphic UAV item - mapcontrol::UAVItem* uav = GetUAV(system->getUASID()); - // Check if reference is valid, else create a new one - if (uav == NULL) - { - MAV2DIcon* newUAV = new MAV2DIcon(map, this, system); - AddUAV(system->getUASID(), newUAV); - uav = newUAV; - uav->SetTrailTime(1); - uav->SetTrailDistance(5); - uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed); - } - - // Set new lat/lon position of UAV icon - double latitude = UASManager::instance()->getHomeLatitude(); - double longitude = UASManager::instance()->getHomeLongitude(); - double altitude = UASManager::instance()->getHomeAltitude(); - internals::PointLatLng pos_lat_lon = internals::PointLatLng(system->getLatitude(), system->getLongitude()); - uav->SetUAVPos(pos_lat_lon, system->getAltitude()); - // Follow status - if (followUAVEnabled && system->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon); - // Convert from radians to degrees and apply - uav->SetUAVHeading((system->getYaw()/M_PI)*180.0f); - } + updateLocalPosition(); } diff --git a/src/ui/mavlink/QGCMAVLinkMessageSender.cc b/src/ui/mavlink/QGCMAVLinkMessageSender.cc index 630d79af303054fc33378be473ad84320e570000..227934f72262897296e8ecc66420f63c5a93fd91 100644 --- a/src/ui/mavlink/QGCMAVLinkMessageSender.cc +++ b/src/ui/mavlink/QGCMAVLinkMessageSender.cc @@ -23,7 +23,6 @@ QGCMAVLinkMessageSender::QGCMAVLinkMessageSender(MAVLinkProtocol* mavlink, QWidg void QGCMAVLinkMessageSender::refresh() { - unsigned int maxUpdateRate = 0; // Send messages foreach (unsigned int i, managementItems.keys()) { @@ -79,7 +78,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset; for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) { - if (field->data(1, Qt::DisplayRole).toString().split(" ").size() > j) + if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j) { nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toInt(); }