diff --git a/deploy/qgroundcontrol_installer.nsi b/deploy/qgroundcontrol_installer.nsi index d2c351a6f692f5b95fe80dd9467bc4edb9d17b33..cef7af550a95e394dc1680a94524deb861700afa 100644 --- a/deploy/qgroundcontrol_installer.nsi +++ b/deploy/qgroundcontrol_installer.nsi @@ -16,7 +16,7 @@ LicenseData ..\license.txt Section "" SetOutPath $INSTDIR - File ..\release\*.* + File /r ..\release\*.* WriteUninstaller $INSTDIR\QGroundControl_uninstall.exe SectionEnd diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri index 874e48fee3afe8631bdf648232bde0400b856e3b..35789238296a666aeef1b4846671184cce192439 100644 --- a/qgroundcontrol.pri +++ b/qgroundcontrol.pri @@ -320,8 +320,14 @@ win32-msvc2008 { message(Building for Windows Visual Studio 2008 (32bit)) + # QAxContainer support is needed for the Internet Control + # element showing the Google Earth window CONFIG += qaxcontainer + # The EIGEN library needs this define + # to make the internal min/max functions work + DEFINES += NOMINMAX + # QWebkit is not needed on MS-Windows compilation environment CONFIG -= webkit diff --git a/src/QGC.h b/src/QGC.h index 6ddd5fc67fd9641221b4d26192496239550bd395..9a1b442d176de3bc7818d086c4cc2f8fa705880f 100644 --- a/src/QGC.h +++ b/src/QGC.h @@ -33,9 +33,22 @@ /* Windows fixes */ #ifdef _MSC_VER -#include -#define isnan(x) _isnan(x) -#define isinf(x) (!_finite(x)) +/* Needed define for Eigen */ +//#define NOMINMAX +#include +template +inline bool isnan(T value) +{ + return value != value; + +} + +// requires #include +template +inline bool isinf(T value) +{ + return std::numeric_limits::has_infinity && (value == std::numeric_limits::infinity() || (-1*value) == std::numeric_limits::infinity()); +} #else #include #ifndef isnan diff --git a/src/comm/MAVLinkSimulationWaypointPlanner.cc b/src/comm/MAVLinkSimulationWaypointPlanner.cc index f2e0acc4836668468b816303cd2e7f3970fdb35a..d78b4d5bfe0e96d38f1a5fd497b2f83474956eb0 100644 --- a/src/comm/MAVLinkSimulationWaypointPlanner.cc +++ b/src/comm/MAVLinkSimulationWaypointPlanner.cc @@ -820,7 +820,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* mavlink_msg_action_decode(msg, &action); if(action.target == systemid) { if (verbose) qDebug("Waypoint: received message with action %d\n", action.action); - switch (action.action) { +// switch (action.action) { // case MAV_ACTION_LAUNCH: // if (verbose) std::cerr << "Launch received" << std::endl; // current_active_wp_id = 0; @@ -847,10 +847,10 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* // default: // if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl; // break; - } +// } } break; - } + } case MAVLINK_MSG_ID_WAYPOINT_ACK: { mavlink_waypoint_ack_t wpa; diff --git a/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 9b61f0bfb23895498af0338752d7c33fc1f5246a..f854c9c989f8832654030ee9f0743f1acc187234 100644 --- a/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -86,7 +86,7 @@ namespace mapcontrol } else if(trailtype==UAVTrailType::ByDistance) { - if(qAbs(internals::PureProjection::DistanceBetweenLatLng(lastcoord,position))>traildistance) + if(qAbs(internals::PureProjection::DistanceBetweenLatLng(lastcoord,position)*1000)>traildistance) { trail->addToGroup(new TrailItem(position,altitude,color,this)); if(!lasttrailline.IsEmpty()) diff --git a/src/uas/QGCUASParamManager.cc b/src/uas/QGCUASParamManager.cc index 82ea6f514323f46d47c65799708ce2771c874d64..d6e9a6bc47befe46296d8df0a4faefc3cba3bff4 100644 --- a/src/uas/QGCUASParamManager.cc +++ b/src/uas/QGCUASParamManager.cc @@ -20,7 +20,7 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : */ void QGCUASParamManager::requestParameterListUpdate(int component) { - + Q_UNUSED(component); } diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 3a5ac60a4d0fdcc2d01127844e27263a2981f662..e186b0a2dc4e31bb8ef588819e2972672569bba5 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -51,20 +51,6 @@ This file is part of the QGROUNDCONTROL project #define GL_MULTISAMPLE 0x809D #endif -template -inline bool isnan(T value) -{ - return value != value; - -} - -// requires #include -template -inline bool isinf(T value) -{ - return std::numeric_limits::has_infinity && (value == std::numeric_limits::infinity() || (-1*value) == std::numeric_limits::infinity()); -} - /** * @warning The HUD widget will not start painting its content automatically * to update the view, start the auto-update by calling HUD::start(). diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc index 659313cae6398aedef5f9ff961d6cad388f0afbc..955e36bb9eb5073895dfb672c30f82b75c7813a8 100644 --- a/src/ui/QGCDataPlot2D.cc +++ b/src/ui/QGCDataPlot2D.cc @@ -405,8 +405,6 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil int curveNameIndex = 0; - //int xValueIndex = curveNames.indexOf(xAxisName); - QString xAxisFilter; if (xAxisName == "") { xAxisFilter = curveNames.first(); @@ -414,6 +412,34 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil xAxisFilter = xAxisName; } + // Fill y-axis renaming lookup table + // Allow the user to rename data dimensions in the plot + QMap renaming; + + QStringList yCurves = yAxisFilter.split("|", QString::SkipEmptyParts); + + // Figure out the correct renaming + for (int i = 0; i < yCurves.count(); ++i) + { + if (yCurves.at(i).contains(":")) + { + QStringList parts = yCurves.at(i).split(":", QString::SkipEmptyParts); + if (parts.count() > 1) + { + // Insert renaming map + renaming.insert(parts.first(), parts.last()); + // Replace curve value with first part only + yCurves.replace(i, parts.first()); + } + } +// else +// { +// // Insert same value, not renaming anything +// renaming.insert(yCurves.at(i), yCurves.at(i)); +// } + } + + foreach(curveName, curveNames) { // Add to plot x axis selection ui->xAxis->addItem(curveName); @@ -421,14 +447,19 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil ui->xRegressionComboBox->addItem(curveName); ui->yRegressionComboBox->addItem(curveName); if (curveName != xAxisFilter) { - if ((yAxisFilter == "") || yAxisFilter.contains(curveName)) { + if ((yAxisFilter == "") || yCurves.contains(curveName)) { yValues.insert(curveName, new QVector()); xValues.insert(curveName, new QVector()); // Add separator starting with second item if (curveNameIndex > 0 && curveNameIndex < curveNames.count()) { ui->yAxis->setText(ui->yAxis->text()+"|"); } - ui->yAxis->setText(ui->yAxis->text()+curveName); + // If this curve was renamed, re-add the renaming to the text field + QString renamingText = ""; + if (renaming.contains(curveName)) renamingText = QString(":%1").arg(renaming.value(curveName)); + ui->yAxis->setText(ui->yAxis->text()+curveName+renamingText); + // Insert same value, not renaming anything + if (!renaming.contains(curveName)) renaming.insert(curveName, curveName); curveNameIndex++; } } @@ -478,7 +509,8 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil foreach(curveName, curveNames) { // Y AXIS HANDLING - if(curveName != xAxisFilter && (yAxisFilter == "" || yAxisFilter.contains(curveName))) + // Only plot non-x curver and those selected in the yAxisFilter (or all if the filter is not set) + if(curveName != xAxisFilter && (yAxisFilter == "" || yCurves.contains(curveName))) { bool oky; int curveNameIndex = curveNames.indexOf(curveName); @@ -504,7 +536,14 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil // Add data array of each curve to the plot at once (fast) // Iterates through all x-y curve combinations for (int i = 0; i < yValues.count(); i++) { - plot->appendData(yValues.keys().at(i), xValues.values().at(i)->data(), yValues.values().at(i)->data(), xValues.values().at(i)->count()); + if (renaming.contains(yValues.keys().at(i))) + { + plot->appendData(renaming.value(yValues.keys().at(i)), xValues.values().at(i)->data(), yValues.values().at(i)->data(), xValues.values().at(i)->count()); + } + else + { + plot->appendData(yValues.keys().at(i), xValues.values().at(i)->data(), yValues.values().at(i)->data(), xValues.values().at(i)->count()); + } } plot->updateScale(); plot->setStyleText(ui->style->currentText()); diff --git a/src/ui/QGCDataPlot2D.ui b/src/ui/QGCDataPlot2D.ui index 04861aebb8bf5716b31f66b2171458b2250d5b86..1cd5288e490948ffd0efc5e01aa3c60132396741 100644 --- a/src/ui/QGCDataPlot2D.ui +++ b/src/ui/QGCDataPlot2D.ui @@ -6,14 +6,14 @@ 0 0 - 1073 - 308 + 1463 + 311 Form - + @@ -303,7 +303,7 @@ - 40 + 5 20 diff --git a/src/ui/map/QGCMapTool.cc b/src/ui/map/QGCMapTool.cc index f7ed1442e89abcf17024d694e9f31c79dd4abad1..ef159c69d578d0301b3173c01dc9e5e711e89489 100644 --- a/src/ui/map/QGCMapTool.cc +++ b/src/ui/map/QGCMapTool.cc @@ -1,5 +1,7 @@ #include "QGCMapTool.h" #include "ui_QGCMapTool.h" +#include +#include QGCMapTool::QGCMapTool(QWidget *parent) : QWidget(parent), diff --git a/src/ui/map/QGCMapTool.h b/src/ui/map/QGCMapTool.h index d7d4f4c4a68b4ceba6747e7aa7ce0771a7c375b7..784bf786252a8e9b61a6a730eb169e7d1df55b5a 100644 --- a/src/ui/map/QGCMapTool.h +++ b/src/ui/map/QGCMapTool.h @@ -2,6 +2,7 @@ #define QGCMAPTOOL_H #include +#include namespace Ui { class QGCMapTool; diff --git a/src/ui/map/QGCMapToolBar.cc b/src/ui/map/QGCMapToolBar.cc index 490a2cd74559712c8ac9ef30b707c4396c5b2ec0..7eed4610aed12e5fe91b4a8c26d865150ea1544d 100644 --- a/src/ui/map/QGCMapToolBar.cc +++ b/src/ui/map/QGCMapToolBar.cc @@ -29,9 +29,42 @@ void QGCMapToolBar::setMap(QGCMapWidget* map) // Edit mode handling ui->editButton->hide(); + +// const int uavTrailTimeList[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; // seconds +// const int uavTrailTimeCount = 10; + +// const int uavTrailDistanceList[] = {1, 2, 5, 10, 20, 50, 100, 200, 500}; // meters +// const int uavTrailDistanceCount = 9; + +// optionsMenu.setParent(this); + + +// // Build up menu +// //trailPlotMenu(tr("Add trail dot every.."), this); +// for (int i = 0; i < uavTrailTimeCount; ++i) +// { +// trailPlotMenu.addAction(QString("%1 second%2").arg(uavTrailTimeList[i]).arg((uavTrailTimeList[i] > 1) ? "s" : ""), this, SLOT(setUAVTrailTime())); +// } +// for (int i = 0; i < uavTrailDistanceCount; ++i) +// { +// trailPlotMenu.addAction(QString("%1 meter%2").arg(uavTrailDistanceList[i]).arg((uavTrailDistanceList[i] > 1) ? "s" : ""), this, SLOT(setUAVTrailDistance())); +// } +// optionsMenu.addMenu(&trailPlotMenu); + +// ui->optionsButton->setMenu(&optionsMenu); } } +void QGCMapToolBar::setUAVTrailTime() +{ + +} + +void QGCMapToolBar::setUAVTrailDistance() +{ + +} + void QGCMapToolBar::tileLoadStart() { ui->posLabel->setText(QString("Starting to load tiles..")); diff --git a/src/ui/map/QGCMapToolBar.h b/src/ui/map/QGCMapToolBar.h index 8b61d776b46a2427d9c60990ef6bf824e1d7484b..d7d4284bd43319f19db850e9cfcf06bf69af4d0f 100644 --- a/src/ui/map/QGCMapToolBar.h +++ b/src/ui/map/QGCMapToolBar.h @@ -2,6 +2,7 @@ #define QGCMAPTOOLBAR_H #include +#include class QGCMapWidget; @@ -23,9 +24,13 @@ public slots: void tileLoadStart(); void tileLoadEnd(); void tileLoadProgress(int progress); + void setUAVTrailTime(); + void setUAVTrailDistance(); protected: QGCMapWidget* map; + QMenu optionsMenu; + QMenu trailPlotMenu; private: Ui::QGCMapToolBar *ui; diff --git a/src/ui/map/QGCMapToolBar.ui b/src/ui/map/QGCMapToolBar.ui index 38f0151fe3c78a2f4f91bb0f75b7fd699f0c0ac1..84d7a8a615bab543a75713fb86cbae7d96356600 100644 --- a/src/ui/map/QGCMapToolBar.ui +++ b/src/ui/map/QGCMapToolBar.ui @@ -69,6 +69,13 @@ + + + + Options + + + diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index 474283b46599747eefffd2719a86ce0e70b0f0ed..744a71fecd6704dd1cd1264b29d9e27b318f75a9 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -26,6 +26,9 @@ QGCMapWidget::~QGCMapWidget() void QGCMapWidget::showEvent(QShowEvent* event) { + // FIXME XXX this is a hack to trick OPs current 1-system design + SetShowUAV(false); + // Pass on to parent widget OPMapWidget::showEvent(event); @@ -57,30 +60,25 @@ void QGCMapWidget::showEvent(QShowEvent* event) // magic_waypoint.time_seconds = 0; // magic_waypoint.hold_time_seconds = 0; - const int safe_area_radius_list[] = {5, 10, 20, 50, 100, 200, 500, 1000, 2000, 5000}; // meters - - const int uav_trail_time_list[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; // seconds - - const int uav_trail_distance_list[] = {1, 2, 5, 10, 20, 50, 100, 200, 500}; // meters - SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions SetFollowMouse(true); // we want a contiuous mouse position reading SetShowHome(true); // display the HOME position on the map - SetShowUAV(true); // display the UAV position on the map +// SetShowUAV(true); // display the UAV position on the map //SetShowDiagnostics(true); // Not needed in flight / production mode - Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) + + Home->SetSafeArea(30); // set radius (meters) Home->SetShowSafeArea(true); // show the safe area -// UAV->SetTrailTime(uav_trail_time_list[0]); // seconds -// UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters +//// UAV->SetTrailTime(uav_trail_time_list[0]); // seconds +//// UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters - // UAV->SetTrailType(UAVTrailType::ByTimeElapsed); - // UAV->SetTrailType(UAVTrailType::ByDistance); +//// UAV->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed); +//// UAV->SetTrailType(mapcontrol::UAVTrailType::ByDistance); - GPS->SetTrailTime(uav_trail_time_list[0]); // seconds - GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters +// GPS->SetTrailTime(uav_trail_time_list[0]); // seconds +// GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters // GPS->SetTrailType(UAVTrailType::ByTimeElapsed); @@ -245,9 +243,9 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo newUAV->setParentItem(map); UAVS.insert(uas->getUASID(), newUAV); uav = GetUAV(uas->getUASID()); -// uav->SetTrailTime(1); -// uav->SetTrailDistance(5); -// uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed); + uav->SetTrailTime(1); + uav->SetTrailDistance(5); + uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed); } // Set new lat/lon position of UAV icon @@ -276,6 +274,9 @@ void QGCMapWidget::updateGlobalPosition() 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