diff --git a/images/earth.html b/images/earth.html
index 6f423cb2604b37f014a83614ee796939fd27aec8..8febdee5129870dbdea324fbadd9dfa632e5f843 100644
--- a/images/earth.html
+++ b/images/earth.html
@@ -13,6 +13,7 @@ google.load("earth", "1", { 'language': 'en'});
var ge = null;
var initialized = false;
+
var aircraft = new Array();
var currAircraft = 220;
var followAircraft = false;
@@ -37,6 +38,9 @@ var currView = null;
var planeOrient;
var planeLoc;
+var trail;
+var lineStringPlacemark;
+var lineStyle;
// Aircraft class
@@ -95,27 +99,9 @@ function setGCSHome(lat, lon, alt)
goHome();
}
-function initCallback(object)
+function createAircraft(id, type, color)
{
- ge = object;
- ge.getWindow().setVisibility(true);
- ge.getOptions().setStatusBarVisibility(true);
- ge.getOptions().setScaleLegendVisibility(true);
- ge.getOptions().setFlyToSpeed(ge.SPEED_TELEPORT);
- ge.getNavigationControl().setVisibility(ge.VISIBILITY_AUTO);
-
- ge.getLayerRoot().enableLayerById(ge.LAYER_TERRAIN, true);
- ge.getLayerRoot().enableLayerById(ge.LAYER_BUILDINGS, true);
- ge.getLayerRoot().enableLayerById(ge.LAYER_BORDERS, true);
- ge.getLayerRoot().enableLayerById(ge.LAYER_TREES, true);
-
- // Now after the Google Earth initialization, initialize the GCS view
- setGCSHome(currLat, currLon, currAlt);
-
-
- // Create the first aircraft model
- // Load 3D model
- var planePlacemark = ge.createPlacemark('');
+ planePlacemark = ge.createPlacemark('');
planePlacemark.setName('aircraft');
planeModel = ge.createModel('');
ge.getFeatures().appendChild(planePlacemark);
@@ -135,9 +121,77 @@ function initCallback(object)
planePlacemark.setGeometry(planeModel);
- setAircraftPositionAttitude(220, 47.3772, currLon, currAlt+50, 20, 15, 50);
- enableFollowing(true);
- updateFollowAircraft();
+ // Write into global structure
+ aircraft[id] = planePlacemark;
+ attitudes[id] = planeOrient;
+ locations[id] = planeLoc;
+
+ //createTrail(id, color);
+}
+
+function createTrail(id, color)
+{
+ lineStringPlacemark = ge.createPlacemark('');
+ // Create the placemark
+// Create the LineString; set it to extend down to the ground
+// and set the altitude mode
+trail = ge.createLineString('');
+lineStringPlacemark.setGeometry(trail);
+trail.setExtrude(true);
+trail.setAltitudeMode(ge.ALTITUDE_ABSOLUTE);
+
+// Add LineString points
+//lineString.getCoordinates().pushLatLngAlt(48.754, -121.835, 700);
+
+// Create a style and set width and color of line
+lineStringPlacemark.setStyleSelector(ge.createStyle(''));
+lineStyle = lineStringPlacemark.getStyleSelector().getLineStyle();
+lineStyle.setWidth(5);
+lineStyle.getColor().set(color);
+//lineStyle.getColor().set(color); // aabbggrr format
+
+// Add the feature to Earth
+ge.getFeatures().appendChild(lineStringPlacemark);
+
+}
+
+function addTrailPosition(id, lat, lon, alt)
+{
+ trail.setExtrude(true);
+trail.setAltitudeMode(ge.ALTITUDE_ABSOLUTE);
+
+// Add LineString points
+//lineString.getCoordinates().pushLatLngAlt(48.754, -121.835, 700);
+trail.getCoordinates().pushLatLngAlt(currLat, currLon, currAlt);
+
+// Create a style and set width and color of line
+lineStringPlacemark.setStyleSelector(ge.createStyle(''));
+lineStyle = lineStringPlacemark.getStyleSelector().getLineStyle();
+lineStyle.setWidth(5);
+lineStyle.getColor().set('99bbaaff');
+//lineStyle.getColor().set(color); // aabbggrr format
+
+// Add the feature to Earth
+ge.getFeatures().replaceChild(lineStringPlacemark, lineStringPlacemark);
+}
+
+function initCallback(object)
+{
+ ge = object;
+ ge.getWindow().setVisibility(true);
+ ge.getOptions().setStatusBarVisibility(true);
+ ge.getOptions().setScaleLegendVisibility(true);
+ ge.getOptions().setFlyToSpeed(ge.SPEED_TELEPORT);
+ ge.getNavigationControl().setVisibility(ge.VISIBILITY_AUTO);
+
+ ge.getLayerRoot().enableLayerById(ge.LAYER_TERRAIN, true);
+ ge.getLayerRoot().enableLayerById(ge.LAYER_BUILDINGS, true);
+ ge.getLayerRoot().enableLayerById(ge.LAYER_BORDERS, true);
+ ge.getLayerRoot().enableLayerById(ge.LAYER_TREES, true);
+
+ createTrail(220, 'bb2222ff');
+ createAircraft(220);
+
initialized = true;
@@ -164,6 +218,18 @@ function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
}
+function enableDaylight(enabled)
+{
+ if(enabled)
+ {
+ ge.getSun().setVisibility(true);
+ }
+ else
+ {
+ ge.getSun().setVisibility(false);
+ }
+}
+
function goHome()
{
var currView = ge.getView().copyAsLookAt(ge.ALTITUDE_ABSOLUTE);
diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri
index c55093543ce1d995d431e849f7ee91d34925dea6..d21ef7c5ccc5e0e7de617740558e9d6ef1c47a3b 100644
--- a/qgroundcontrol.pri
+++ b/qgroundcontrol.pri
@@ -154,6 +154,7 @@ linux-g++ {
release {
DESTDIR = $$TARGETDIR/release
+ DEFINES += QT_NO_DEBUG
}
QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
@@ -223,6 +224,7 @@ linux-g++-64 {
release {
DESTDIR = $$TARGETDIR/release
+ DEFINES += QT_NO_DEBUG
}
QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
@@ -295,6 +297,7 @@ win32-msvc2008 {
release {
CONFIG -= console
+ DEFINES += QT_NO_DEBUG
}
debug {
@@ -382,6 +385,7 @@ win32-g++ {
release {
CONFIG -= console
+ DEFINES += QT_NO_DEBUG
#DESTDIR = $$BUILDDIR/release
}
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 1d761bbba036c6cc36c7cf6f44f6fde7586fa984..eadd028c0d79f9b5d678f5f7621b9e993b4faae3 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -245,7 +245,6 @@ HEADERS += src/MG.h \
src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \
src/ui/map3D/QGCWebPage.h \
- src/ui/map3D/QGCGoogleEarthView.h\
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
@@ -255,6 +254,11 @@ HEADERS += src/MG.h \
src/comm/MAVLinkSwarmSimulationLink.h \
src/ui/uas/QGCUnconnectedInfoWidget.h
+# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
+macx|win32-msvc2008: {
+ HEADERS += src/ui/map3D/QGCGoogleEarthView.h
+}
+
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
@@ -357,7 +361,6 @@ SOURCES += src/main.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \
- src/ui/map3D/QGCGoogleEarthView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
@@ -367,6 +370,11 @@ SOURCES += src/main.cc \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc
+
+macx|win32-msvc2008: {
+ SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
+}
+
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
diff --git a/src/QGC.h b/src/QGC.h
index 4751cdda47404bea2c0d454f84ad560f51984ea7..c4e4fed4b4c0b33d2dd61fd6cde677b51bee80bc 100644
--- a/src/QGC.h
+++ b/src/QGC.h
@@ -19,4 +19,6 @@ namespace QGC
const QString COMPANYNAME = "OPENMAV";
}
+#define QGC_EVENTLOOP_DEBUG 0
+
#endif // QGC_H
diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc
index 6a909edcbefed6fbdc30121ae470ad0158fb5723..ed67251bfed6263c07566ba55c8a4511ad77bac7 100644
--- a/src/comm/MAVLinkSimulationLink.cc
+++ b/src/comm/MAVLinkSimulationLink.cc
@@ -192,6 +192,7 @@ void MAVLinkSimulationLink::mainloop()
static unsigned int rate1hzCounter = 1;
static unsigned int rate10hzCounter = 1;
static unsigned int rate50hzCounter = 1;
+ static unsigned int circleCounter = 0;
// Vary values
@@ -374,17 +375,20 @@ void MAVLinkSimulationLink::mainloop()
// Move X Position
- x = x*0.93f + 0.07f*(x+sin(static_cast(QGC::groundTimeUsecs()) * 0.08f));
- y = y*0.93f + 0.07f*(y+sin(static_cast(QGC::groundTimeUsecs()) * 0.5f));
- z = z*0.93f + 0.07f*(z+sin(static_cast(QGC::groundTimeUsecs()*0.001f)) * 0.1f);
+ x = 8.0*sin((double)circleCounter/50.0);
+ y = 3.0*cos((double)circleCounter/40.0);
+ z = 1.8 + 1.2*sin((double)circleCounter/60.0);
- x = (x > 5.0f) ? 5.0f : x;
- y = (y > 5.0f) ? 5.0f : y;
- z = (z > 3.0f) ? 3.0f : z;
+ circleCounter++;
- x = (x < -5.0f) ? -5.0f : x;
- y = (y < -5.0f) ? -5.0f : y;
- z = (z < -3.0f) ? -3.0f : z;
+
+// x = (x > 5.0f) ? 5.0f : x;
+// y = (y > 5.0f) ? 5.0f : y;
+// z = (z > 3.0f) ? 3.0f : z;
+
+// x = (x < -5.0f) ? -5.0f : x;
+// y = (y < -5.0f) ? -5.0f : y;
+// z = (z < -3.0f) ? -3.0f : z;
// Send back new setpoint
mavlink_message_t ret;
@@ -401,15 +405,15 @@ void MAVLinkSimulationLink::mainloop()
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
- // GPS RAW
- mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.00001), 8.548103+(y*0.00001), z, 0, 0, 2.5f, 0.1f);
- bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
- //add data into datastream
- memcpy(stream+streampointer,buffer, bufferlength);
- streampointer += bufferlength;
+// // GPS RAW
+// mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.00001), 8.548103+(y*0.00001), z, 0, 0, 2.5f, 0.1f);
+// bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
+// //add data into datastream
+// memcpy(stream+streampointer,buffer, bufferlength);
+// streampointer += bufferlength;
// GLOBAL POSITION
- mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 47.378028137103+(x*0.00001), 8.54899892510421+(y*0.00001), z, 0, 0, 0);
+ mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 47.378028137103+(x*0.001), 8.54899892510421+(y*0.001), z+25.0, 0, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
@@ -508,6 +512,7 @@ void MAVLinkSimulationLink::mainloop()
detectionCounter++;
status.vbat = voltage * 1000; // millivolts
+ status.load = 33 * detectionCounter % 1000;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
@@ -520,7 +525,7 @@ void MAVLinkSimulationLink::mainloop()
// Pack debug text message
mavlink_statustext_t text;
text.severity = 0;
- strcpy((char*)(text.text), "DEBUG MESSAGE TEXT");
+ strcpy((char*)(text.text), "Text message from system 32");
mavlink_msg_statustext_encode(systemId, componentId, &msg, &text);
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
memcpy(stream+streampointer, buffer, bufferlength);
@@ -578,11 +583,11 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
- /*
+
// HEARTBEAT VEHICLE 2
// Pack message and get size of encoded byte string
- messageSize = mavlink_msg_heartbeat_pack(42, componentId, &msg, MAV_FIXED_WING);
+ messageSize = mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
@@ -590,25 +595,19 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// STATUS VEHICLE 2
- sys_status_t status2;
+ mavlink_sys_status_t status2;
status2.mode = MAV_MODE_LOCKED;
status2.vbat = voltage;
+ status2.load = 120;
status2.status = MAV_STATE_STANDBY;
// Pack message and get size of encoded byte string
- messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
+ messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
- */
- //qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer;
-
- // AUX STATUS
- #ifdef MAVLINK_ENABLED_PIXHAWK
- rawAuxValues.vbat = voltage;
-#endif
rate1hzCounter = 1;
}
@@ -780,31 +779,6 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
j++;
}
- /*
- // Pack message and get size of encoded byte string
- mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)"ROLL_K_P", 0.5f);
- // Allocate buffer with packet data
- bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
- //add data into datastream
- memcpy(stream+streampointer,buffer, bufferlength);
- streampointer+=bufferlength;
-
- // Pack message and get size of encoded byte string
- mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)"PITCH_K_P", 0.6f);
- // Allocate buffer with packet data
- bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
- //add data into datastream
- memcpy(stream+streampointer,buffer, bufferlength);
- streampointer+=bufferlength;
-
- // Pack message and get size of encoded byte string
- mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)"YAW_K_P", 0.8f);
- // Allocate buffer with packet data
- bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
- //add data into datastream
- memcpy(stream+streampointer,buffer, bufferlength);
- streampointer+=bufferlength;*/
-
qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
}
}
diff --git a/src/comm/MAVLinkSimulationLink.h b/src/comm/MAVLinkSimulationLink.h
index db40af5b292dc102cd90035f9e159a81abf7bbc3..25ad3ecb1b8977084909330b60776873a543310d 100644
--- a/src/comm/MAVLinkSimulationLink.h
+++ b/src/comm/MAVLinkSimulationLink.h
@@ -94,8 +94,8 @@ protected:
// UAS properties
float roll, pitch, yaw;
- float x, y, z;
- float spX, spY, spZ, spYaw;
+ double x, y, z;
+ double spX, spY, spZ, spYaw;
int battery;
QTimer* timer;
diff --git a/src/configuration.h b/src/configuration.h
index 3420e0f39a6bf6678f63ee613042781b1df6142f..64a17c93f3cec5848b3f58224680536fb926dd5a 100644
--- a/src/configuration.h
+++ b/src/configuration.h
@@ -7,7 +7,7 @@
#ifdef MAVLINK_ENABLED_SLUGS
#define SERIAL_POLL_INTERVAL 7
#else
- #define SERIAL_POLL_INTERVAL 2
+ #define SERIAL_POLL_INTERVAL 7
#endif
/** @brief Heartbeat emission rate, in Hertz (times per second) */
@@ -16,6 +16,6 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
-#define QGC_APPLICATION_VERSION "v. 0.7.7 (Beta)"
+#define QGC_APPLICATION_VERSION "v. 0.8.0 (Beta)"
#endif // CONFIGURATION_H
diff --git a/src/uas/ArduPilotMegaMAV.cc b/src/uas/ArduPilotMegaMAV.cc
index e43003ebc7e8ef463938c659e3052328adb75a16..f87ebc9dd7031dcec77f4d253d2158d27f34ee67 100644
--- a/src/uas/ArduPilotMegaMAV.cc
+++ b/src/uas/ArduPilotMegaMAV.cc
@@ -1,5 +1,4 @@
/*=====================================================================
-
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT
@@ -10,15 +9,15 @@ This file is part of the QGROUNDCONTROL project
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
-
+
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
-
+
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see .
-
+
======================================================================*/
/**
@@ -47,17 +46,20 @@ void ArduPilotMegaMAV::receiveMessage(LinkInterface* link, mavlink_message_t mes
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
-
- // Handle your special messages
- switch (message.msgid)
+
+ if (message.sysid == uasId)
{
- case MAVLINK_MSG_ID_HEARTBEAT:
+ // Handle your special messages
+ switch (message.msgid)
{
- qDebug() << "ARDUPILOT RECEIVED HEARTBEAT";
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ {
+ qDebug() << "ARDUPILOT RECEIVED HEARTBEAT";
+ break;
+ }
+ default:
+ qDebug() << "\nARDUPILOT RECEIVED MESSAGE WITH ID" << message.msgid;
break;
}
- default:
- qDebug() << "\nARDUPILOT RECEIVED MESSAGE WITH ID" << message.msgid;
- break;
}
}
diff --git a/src/uas/SlugsMAV.cc b/src/uas/SlugsMAV.cc
index edc2a4d3bc6b7c7b2d22927a6d0b10f0648ba054..7692bd4966a2ffa7e301131d75c0831fccf676ff 100644
--- a/src/uas/SlugsMAV.cc
+++ b/src/uas/SlugsMAV.cc
@@ -60,100 +60,102 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
- UAS::receiveMessage(link, message);
+ UAS::receiveMessage(link, message);
-
- // Handle your special messages mavlink_message_t* msg = &message;
- switch (message.msgid)
+ if (message.sysid == uasId)
{
+ // Handle your special messages mavlink_message_t* msg = &message;
+ switch (message.msgid)
+ {
#ifdef MAVLINK_ENABLED_SLUGS
- case MAVLINK_MSG_ID_BOOT:
- mavlink_msg_boot_decode(&message,&mlBoot);
- emit slugsBootMsg(uasId, mlBoot);
- break;
+ case MAVLINK_MSG_ID_BOOT:
+ mavlink_msg_boot_decode(&message,&mlBoot);
+ emit slugsBootMsg(uasId, mlBoot);
+ break;
- case MAVLINK_MSG_ID_ATTITUDE:
- mavlink_msg_attitude_decode(&message, &mlAttitude);
- break;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ mavlink_msg_attitude_decode(&message, &mlAttitude);
+ break;
- case MAVLINK_MSG_ID_GPS_RAW:
- mavlink_msg_gps_raw_decode(&message, &mlGpsData);
+ case MAVLINK_MSG_ID_GPS_RAW:
+ mavlink_msg_gps_raw_decode(&message, &mlGpsData);
break;
- case MAVLINK_MSG_ID_ACTION_ACK: // 62
- mavlink_msg_action_ack_decode(&message,&mlActionAck);
+ case MAVLINK_MSG_ID_ACTION_ACK: // 62
+ mavlink_msg_action_ack_decode(&message,&mlActionAck);
break;
- case MAVLINK_MSG_ID_CPU_LOAD: //170
- mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
+ case MAVLINK_MSG_ID_CPU_LOAD: //170
+ mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
break;
- case MAVLINK_MSG_ID_AIR_DATA: //171
- mavlink_msg_air_data_decode(&message,&mlAirData);
+ case MAVLINK_MSG_ID_AIR_DATA: //171
+ mavlink_msg_air_data_decode(&message,&mlAirData);
break;
- case MAVLINK_MSG_ID_SENSOR_BIAS: //172
- mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
- break;
+ case MAVLINK_MSG_ID_SENSOR_BIAS: //172
+ mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
+ break;
- case MAVLINK_MSG_ID_DIAGNOSTIC: //173
- mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
- break;
+ case MAVLINK_MSG_ID_DIAGNOSTIC: //173
+ mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
+ break;
- case MAVLINK_MSG_ID_PILOT_CONSOLE: //174
- mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
+ case MAVLINK_MSG_ID_PILOT_CONSOLE: //174
+ mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
break;
- case MAVLINK_MSG_ID_PWM_COMMANDS: //175
- mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
- break;
+ case MAVLINK_MSG_ID_PWM_COMMANDS: //175
+ mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
+ break;
- case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
- mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
+ case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
+ mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
break;
- case MAVLINK_MSG_ID_DATA_LOG: //177
- mavlink_msg_data_log_decode(&message,&mlDataLog);
- break;
+ case MAVLINK_MSG_ID_DATA_LOG: //177
+ mavlink_msg_data_log_decode(&message,&mlDataLog);
+ break;
- case MAVLINK_MSG_ID_FILTERED_DATA: //178
- mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
- break;
+ case MAVLINK_MSG_ID_FILTERED_DATA: //178
+ mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
+ break;
- case MAVLINK_MSG_ID_GPS_DATE_TIME: //179
- mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
+ case MAVLINK_MSG_ID_GPS_DATE_TIME: //179
+ mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
break;
- case MAVLINK_MSG_ID_MID_LVL_CMDS: //180
+ case MAVLINK_MSG_ID_MID_LVL_CMDS: //180
- break;
+ break;
- case MAVLINK_MSG_ID_CTRL_SRFC_PT: //181
+ case MAVLINK_MSG_ID_CTRL_SRFC_PT: //181
break;
- case MAVLINK_MSG_ID_PID: //182
- memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
- mavlink_msg_pid_decode(&message, &mlSinglePid);
- qDebug() << "\nSLUGS RECEIVED PID Message = "<uas != NULL && this->uas != uas)
+ if (this->uas != NULL)
{
// Disconnect any previously connected active MAV
- disconnect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
+ disconnect(this->uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
}
// Now connect the new UAS
- //if (this->uas != uas)
- // {
//qDebug() << "UAS SET!" << "ID:" << uas->getUASID();
// Setup communication
connect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
- //}
this->uas = uas;
}
@@ -663,16 +664,19 @@ void HDDisplay::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
- if (!event->spontaneous())
+ Q_UNUSED(event)
{
- if (event->type() == QEvent::Hide)
- {
- refreshTimer->stop();
- }
- else if (event->type() == QEvent::Show)
- {
- refreshTimer->start(updateInterval);
- }
+ refreshTimer->start(updateInterval);
+ }
+}
+
+void HDDisplay::hideEvent(QHideEvent* event)
+{
+ // React only to internal (pre-display)
+ // events
+ Q_UNUSED(event)
+ {
+ refreshTimer->stop();
}
}
diff --git a/src/ui/HDDisplay.h b/src/ui/HDDisplay.h
index ff988a0b0ca84084f846a26faea31b95286d4d6e..35121b560365c233ad47d6693e04f7cc6ffd05ff 100644
--- a/src/ui/HDDisplay.h
+++ b/src/ui/HDDisplay.h
@@ -76,6 +76,7 @@ protected:
void changeEvent(QEvent *e);
void paintEvent(QPaintEvent * event);
void showEvent(QShowEvent* event);
+ void hideEvent(QHideEvent* event);
float refLineWidthToPen(float line);
float refToScreenX(float x);
float refToScreenY(float y);
diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc
index b08a9ec228a24639e96af0dca7ed869227dffbb0..6b547aced32ae751a8193d127903251051848479 100644
--- a/src/ui/HSIDisplay.cc
+++ b/src/ui/HSIDisplay.cc
@@ -103,7 +103,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
refreshTimer->setInterval(updateInterval);
-// this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this));
+ // this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this));
xCenterPos = vwidth/2.0f;
yCenterPos = vheight/2.0f + topMargin - bottomMargin;
@@ -138,6 +138,9 @@ void HSIDisplay::paintEvent(QPaintEvent * event)
void HSIDisplay::renderOverlay()
{
+#if (QGC_EVENTLOOP_DEBUG)
+ qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
+#endif
// Center location of the HSI gauge items
float bottomMargin = 3.0f;
@@ -432,43 +435,46 @@ void HSIDisplay::setMetricWidth(double width)
*/
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
- if (this->uas != NULL && this->uas != uas)
- {
- // Disconnect any previously connected active MAV
- //disconnect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
- }
-
-
- HDDisplay::setActiveUAS(uas);
- //qDebug() << "ATTEMPTING TO SET UAS";
-
-
- connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
- connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
- connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
- connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
- connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
- connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
- connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
+ if (this->uas != NULL)
+ {
+ disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
+ disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
+ disconnect(this->uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
+ disconnect(this->uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
+ disconnect(this->uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
+ disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
+ disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
+
+ disconnect(this->uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
+ disconnect(this->uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
+ disconnect(this->uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
+ disconnect(this->uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
+
+ disconnect(this->uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
+ disconnect(this->uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
+ disconnect(this->uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
+ disconnect(this->uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
+ }
- connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
- connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
- connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
- connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
+ connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
+ connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
+ connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
+ connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
+ connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
+ connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
+ connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
- connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
- connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
- connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
- connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
+ connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
+ connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
+ connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
+ connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
- // Now connect the new UAS
+ connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
+ connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
+ connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
+ connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
- //if (this->uas != uas)
- // {
- //qDebug() << "UAS SET!" << "ID:" << uas->getUASID();
- // Setup communication
- //connect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
- //}
+ this->uas = uas;
}
void HSIDisplay::updateSpeed(UASInterface* uas, double vx, double vy, double vz, quint64 time)
@@ -667,18 +673,18 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
if (uas)
{
const QVector& list = uas->getWaypointManager().getWaypointList();
-// for (int i = 0; i < list.size(); i++)
-// {
-// QPointF in(list.at(i)->getX(), list.at(i)->getY());
-// // Transform from world to body coordinates
-// in = metricWorldToBody(in);
-// // Scale from metric to screen reference coordinates
-// QPointF p = metricBodyToRef(in);
-// Waypoint2DIcon* wp = new Waypoint2DIcon();
-// wp->setLocalPosition(list.at(i)->getX(), list.at(i)->getY());
-// wp->setPos(0, 0);
-// scene()->addItem(wp);
-// }
+ // for (int i = 0; i < list.size(); i++)
+ // {
+ // QPointF in(list.at(i)->getX(), list.at(i)->getY());
+ // // Transform from world to body coordinates
+ // in = metricWorldToBody(in);
+ // // Scale from metric to screen reference coordinates
+ // QPointF p = metricBodyToRef(in);
+ // Waypoint2DIcon* wp = new Waypoint2DIcon();
+ // wp->setLocalPosition(list.at(i)->getX(), list.at(i)->getY());
+ // wp->setPos(0, 0);
+ // scene()->addItem(wp);
+ // }
QColor color;
painter.setBrush(Qt::NoBrush);
@@ -929,16 +935,19 @@ void HSIDisplay::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
- if (!event->spontaneous())
+ Q_UNUSED(event)
{
- if (event->type() == QEvent::Hide)
- {
- refreshTimer->stop();
- }
- else if (event->type() == QEvent::Show)
- {
- refreshTimer->start(updateInterval);
- }
+ refreshTimer->start(updateInterval);
+ }
+}
+
+void HSIDisplay::hideEvent(QHideEvent* event)
+{
+ // React only to internal (post-display)
+ // events
+ Q_UNUSED(event)
+ {
+ refreshTimer->stop();
}
}
diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h
index b67f1726f7d9083e92c8acc42ceec9b0362df7dd..c70598e41daccd19dfc9f2142ff2afb3179ae76f 100644
--- a/src/ui/HSIDisplay.h
+++ b/src/ui/HSIDisplay.h
@@ -112,6 +112,7 @@ protected slots:
protected:
void showEvent(QShowEvent* event);
+ void hideEvent(QHideEvent* event);
/** @brief Get color from GPS signal-to-noise colormap */
static QColor getColorForSNR(float snr);
/** @brief Metric world coordinates to metric body coordinates */
diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc
index 6e40c1c016a2d6f73e3bf7544e5d229af4b4eb31..ad090a1c7530b1b00d950f7a524657ea40ac9a2a 100644
--- a/src/ui/HUD.cc
+++ b/src/ui/HUD.cc
@@ -41,6 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASManager.h"
#include "HUD.h"
#include "MG.h"
+#include "QGC.h"
// Fix for some platforms, e.g. windows
#ifndef GL_MULTISAMPLE
@@ -179,16 +180,19 @@ void HUD::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
- if (!event->spontaneous())
+ Q_UNUSED(event)
{
- if (event->type() == QEvent::Hide)
- {
- refreshTimer->stop();
- }
- else if (event->type() == QEvent::Show)
- {
- refreshTimer->start(updateInterval);
- }
+ refreshTimer->start(updateInterval);
+ }
+}
+
+void HUD::hideEvent(QHideEvent* event)
+{
+ // React only to internal (pre-display)
+ // events
+ Q_UNUSED(event)
+ {
+ refreshTimer->stop();
}
}
@@ -561,6 +565,10 @@ void HUD::paintHUD()
// qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
// interval = MG::TIME::getGroundTimeNow();
+#if (QGC_EVENTLOOP_DEBUG)
+ qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
+#endif
+
// Read out most important values to limit hash table lookups
static float roll = 0.0f;
static float pitch = 0.0f;
diff --git a/src/ui/HUD.h b/src/ui/HUD.h
index de172295e47531333a4a9daff3c33193007470ca..f5f4695f28b490316526bef6aa5b90e56a186277 100644
--- a/src/ui/HUD.h
+++ b/src/ui/HUD.h
@@ -118,8 +118,10 @@ protected:
float refLineWidthToPen(float line);
/** @brief Rotate a polygon around a point clockwise */
void rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin);
- /** @brief Override base class show */
+ /** @brief Start updating widget */
void showEvent(QShowEvent* event);
+ /** @brief Stop updating widget */
+ void hideEvent(QHideEvent* event);
static const int updateInterval = 50;
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index be2b33fce1d95385d09401cacd892e7d0310eb7d..ddad6c027da283c9f15925499f1dd1a09bb92c6c 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -40,16 +40,16 @@
MainWindow* MainWindow::instance()
{
- static MainWindow* _instance = 0;
- if(_instance == 0)
- {
- _instance = new MainWindow();
+ static MainWindow* _instance = 0;
+ if(_instance == 0)
+ {
+ _instance = new MainWindow();
- /* Set the application as parent to ensure that this object
+ /* Set the application as parent to ensure that this object
* will be destroyed when the main application exits */
- //_instance->setParent(qApp);
- }
- return _instance;
+ //_instance->setParent(qApp);
+ }
+ return _instance;
}
/**
@@ -74,9 +74,14 @@ MainWindow::MainWindow(QWidget *parent):
if (!settings.contains(centralKey))
{
settings.setValue(centralKey,true);
- QString listKey = buildMenuKey(SUB_SECTION_CHECKED, MENU_UAS_LIST, currentView);
+ }
+
+ QString listKey = buildMenuKey(SUB_SECTION_CHECKED, MENU_UAS_LIST, currentView);
+ if (!settings.contains(listKey))
+ {
settings.setValue(listKey, true);
}
+
settings.sync();
// Setup user interface
@@ -103,11 +108,22 @@ MainWindow::MainWindow(QWidget *parent):
// Create actions
connectCommonActions();
+ // Set dock options
+ setDockOptions(AnimatedDocks | AllowTabbedDocks | AllowNestedDocks);
+
// Load mavlink view as default widget set
//loadMAVLinkView();
- // Adjust the size
- adjustSize();
+ if (settings.contains("geometry"))
+ {
+ // Restore the window geometry
+ restoreGeometry(settings.value("geometry").toByteArray());
+ }
+ else
+ {
+ // Adjust the size
+ adjustSize();
+ }
// Populate link menu
QList links = LinkManager::instance()->getLinks();
@@ -132,32 +148,53 @@ void MainWindow::buildCommonWidgets()
mavlink = new MAVLinkProtocol();
// Dock widgets
- controlDockWidget = new QDockWidget(tr("Control"), this);
- controlDockWidget->setWidget( new UASControlWidget(this) );
- addToToolsMenu (controlDockWidget, tr("Control"), SLOT(showToolWidget()), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea);
+ if (!controlDockWidget)
+ {
+ controlDockWidget = new QDockWidget(tr("Control"), this);
+ controlDockWidget->setWidget( new UASControlWidget(this) );
+ addToToolsMenu (controlDockWidget, tr("Control"), SLOT(showToolWidget()), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea);
+ }
- listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
- listDockWidget->setWidget( new UASListWidget(this) );
- addToToolsMenu (listDockWidget, tr("Unmanned Systems"), SLOT(showToolWidget()), MENU_UAS_LIST, Qt::RightDockWidgetArea);
+ if (!listDockWidget)
+ {
+ listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
+ listDockWidget->setWidget( new UASListWidget(this) );
+ addToToolsMenu (listDockWidget, tr("Unmanned Systems"), SLOT(showToolWidget()), MENU_UAS_LIST, Qt::RightDockWidgetArea);
+ }
- waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
- waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
- addToToolsMenu (waypointsDockWidget, tr("Waypoints List"), SLOT(showToolWidget()), MENU_WAYPOINTS, Qt::BottomDockWidgetArea);
+ if (!waypointsDockWidget)
+ {
+ waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
+ waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
+ addToToolsMenu (waypointsDockWidget, tr("Waypoints List"), SLOT(showToolWidget()), MENU_WAYPOINTS, Qt::BottomDockWidgetArea);
+ }
- infoDockWidget = new QDockWidget(tr("Status Details"), this);
- infoDockWidget->setWidget( new UASInfoWidget(this) );
- addToToolsMenu (infoDockWidget, tr("Status Details"), SLOT(showToolWidget()), MENU_STATUS, Qt::RightDockWidgetArea);
+ if (!infoDockWidget)
+ {
+ infoDockWidget = new QDockWidget(tr("Status Details"), this);
+ infoDockWidget->setWidget( new UASInfoWidget(this) );
+ addToToolsMenu (infoDockWidget, tr("Status Details"), SLOT(showToolWidget()), MENU_STATUS, Qt::RightDockWidgetArea);
+ }
- debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
- debugConsoleDockWidget->setWidget( new DebugConsole(this) );
- addToToolsMenu (debugConsoleDockWidget, tr("Communication Console"), SLOT(showToolWidget()), MENU_DEBUG_CONSOLE, Qt::BottomDockWidgetArea);
+ if (!debugConsoleDockWidget)
+ {
+ debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
+ debugConsoleDockWidget->setWidget( new DebugConsole(this) );
+ addToToolsMenu (debugConsoleDockWidget, tr("Communication Console"), SLOT(showToolWidget()), MENU_DEBUG_CONSOLE, Qt::BottomDockWidgetArea);
+ }
// Center widgets
- mapWidget = new MapWidget(this);
- addToCentralWidgetsMenu (mapWidget, "Maps", SLOT(showCentralWidget()),CENTRAL_MAP);
+ if (!mapWidget)
+ {
+ mapWidget = new MapWidget(this);
+ addToCentralWidgetsMenu (mapWidget, "Maps", SLOT(showCentralWidget()),CENTRAL_MAP);
+ }
- protocolWidget = new XMLCommProtocolWidget(this);
- addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL);
+ if (!protocolWidget)
+ {
+ protocolWidget = new XMLCommProtocolWidget(this);
+ addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL);
+ }
}
void MainWindow::buildPxWidgets()
@@ -176,109 +213,169 @@ void MainWindow::buildPxWidgets()
acceptList2->append("Battery");
acceptList2->append("Pressure");
- // Center widgets
- linechartWidget = new Linecharts(this);
- addToCentralWidgetsMenu(linechartWidget, "Line Plots", SLOT(showCentralWidget()), CENTRAL_LINECHART);
+ if (!linechartWidget)
+ {
+ // Center widgets
+ linechartWidget = new Linecharts(this);
+ addToCentralWidgetsMenu(linechartWidget, "Line Plots", SLOT(showCentralWidget()), CENTRAL_LINECHART);
+ }
- hudWidget = new HUD(320, 240, this);
- addToCentralWidgetsMenu(hudWidget, "HUD", SLOT(showCentralWidget()), CENTRAL_HUD);
+ if (!hudWidget)
+ {
+ hudWidget = new HUD(320, 240, this);
+ addToCentralWidgetsMenu(hudWidget, "HUD", SLOT(showCentralWidget()), CENTRAL_HUD);
+ }
- dataplotWidget = new QGCDataPlot2D(this);
- addToCentralWidgetsMenu(dataplotWidget, "Data Plots", SLOT(showCentralWidget()), CENTRAL_DATA_PLOT);
+ if (!dataplotWidget)
+ {
+ dataplotWidget = new QGCDataPlot2D(this);
+ addToCentralWidgetsMenu(dataplotWidget, "Data Plots", SLOT(showCentralWidget()), CENTRAL_DATA_PLOT);
+ }
#ifdef QGC_OSG_ENABLED
- _3DWidget = Q3DWidgetFactory::get("PIXHAWK");
- addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
-
+ if (!_3DWidget)
+ {
+ _3DWidget = Q3DWidgetFactory::get("PIXHAWK");
+ addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
+ }
#endif
#ifdef QGC_OSGEARTH_ENABLED
- _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
- addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
+ if (!_3DMapWidget)
+ {
+ _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
+ addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
+ }
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
- gEarthWidget = new QGCGoogleEarthView(this);
- addToCentralWidgetsMenu(gEarthWidget, "Google Earth", SLOT(showCentralWidget()), CENTRAL_GOOGLE_EARTH);
+ if (!gEarthWidget)
+ {
+ gEarthWidget = new QGCGoogleEarthView(this);
+ addToCentralWidgetsMenu(gEarthWidget, "Google Earth", SLOT(showCentralWidget()), CENTRAL_GOOGLE_EARTH);
+ }
#endif
// Dock widgets
- detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
- detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
- addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget()), MENU_DETECTION, Qt::RightDockWidgetArea);
-
-
- parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
- parametersDockWidget->setWidget( new ParameterInterface(this) );
- addToToolsMenu (parametersDockWidget, tr("Onboard Parameters"), SLOT(showToolWidget()), MENU_PARAMETERS, Qt::RightDockWidgetArea);
+ if (!detectionDockWidget)
+ {
+ detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
+ detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
+ addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget()), MENU_DETECTION, Qt::RightDockWidgetArea);
+ }
- watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
- watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
- addToToolsMenu (watchdogControlDockWidget, tr("Process Control"), SLOT(showToolWidget()), MENU_WATCHDOG, Qt::BottomDockWidgetArea);
+ if (!parametersDockWidget)
+ {
+ parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
+ parametersDockWidget->setWidget( new ParameterInterface(this) );
+ addToToolsMenu (parametersDockWidget, tr("Onboard Parameters"), SLOT(showToolWidget()), MENU_PARAMETERS, Qt::RightDockWidgetArea);
+ }
+ if (!watchdogControlDockWidget)
+ {
+ watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
+ watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
+ addToToolsMenu (watchdogControlDockWidget, tr("Process Control"), SLOT(showToolWidget()), MENU_WATCHDOG, Qt::BottomDockWidgetArea);
+ }
- hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
- hsiDockWidget->setWidget( new HSIDisplay(this) );
- addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget()), MENU_HSI, Qt::BottomDockWidgetArea);
+ if (!hsiDockWidget)
+ {
+ hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
+ hsiDockWidget->setWidget( new HSIDisplay(this) );
+ addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget()), MENU_HSI, Qt::BottomDockWidgetArea);
+ }
- headDown1DockWidget = new QDockWidget(tr("System Stats"), this);
- headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
- addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
+ if (!headDown1DockWidget)
+ {
+ headDown1DockWidget = new QDockWidget(tr("System Stats"), this);
+ headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
+ addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
+ }
- headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
- headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
- addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea);
+ if (!headDown2DockWidget)
+ {
+ headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
+ headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
+ addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea);
+ }
- rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
- rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
- addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
+ if (!rcViewDockWidget)
+ {
+ rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
+ rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
+ addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
+ }
- headUpDockWidget = new QDockWidget(tr("HUD"), this);
- headUpDockWidget->setWidget( new HUD(320, 240, this));
- addToToolsMenu (headUpDockWidget, tr("Control Indicator"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
+ if (!headUpDockWidget)
+ {
+ headUpDockWidget = new QDockWidget(tr("HUD"), this);
+ headUpDockWidget->setWidget( new HUD(320, 240, this));
+ addToToolsMenu (headUpDockWidget, tr("Control Indicator"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
+ }
// Dialogue widgets
//FIXME: free memory in destructor
- joystick = new JoystickInput();
+ if (!joystick)
+ {
+ joystick = new JoystickInput();
+ }
}
void MainWindow::buildSlugsWidgets()
{
- // Center widgets
- linechartWidget = new Linecharts(this);
-
- // Dock widgets
- headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
- headUpDockWidget->setWidget( new HUD(320, 240, this));
- addToToolsMenu (headUpDockWidget, tr("HUD"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
-
-
- rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
- rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
- addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
+ if (!linechartWidget)
+ {
+ // Center widgets
+ linechartWidget = new Linecharts(this);
+ }
+ if (!headUpDockWidget)
+ {
+ // Dock widgets
+ headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
+ headUpDockWidget->setWidget( new HUD(320, 240, this));
+ addToToolsMenu (headUpDockWidget, tr("HUD"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
+ }
- // Dialog widgets
- slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
- slugsDataWidget->setWidget( new SlugsDataSensorView(this));
- addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
+ if (!rcViewDockWidget)
+ {
+ rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
+ rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
+ addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
+ }
- slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
- slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
- addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
+ if (!slugsDataWidget)
+ {
+ // Dialog widgets
+ slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
+ slugsDataWidget->setWidget( new SlugsDataSensorView(this));
+ addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
+ }
- slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
- slugsHilSimWidget->setWidget( new SlugsHilSim(this));
- addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
+ if (!slugsPIDControlWidget)
+ {
+ slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
+ slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
+ addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
+ }
- slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this);
- slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
- addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
+ if (!slugsHilSimWidget)
+ {
+ slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
+ slugsHilSimWidget->setWidget( new SlugsHilSim(this));
+ addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
+ }
+ if (!slugsCamControlWidget)
+ {
+ slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this);
+ slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
+ addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
+ }
}
@@ -486,13 +583,13 @@ void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view)
tempLocation = static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,widget, view), QVariant(Qt::RightDockWidgetArea)).toInt());
-// if (widget == MainWindow::MENU_UAS_LIST)
-// {
-// if (!settings.contains(buildMenuKey (SUB_SECTION_LOCATION,widget, view)))
-// {
-// tempLocation = Qt::RightDockWidgetArea;
-// }
-// }
+ // if (widget == MainWindow::MENU_UAS_LIST)
+ // {
+ // if (!settings.contains(buildMenuKey (SUB_SECTION_LOCATION,widget, view)))
+ // {
+ // tempLocation = Qt::RightDockWidgetArea;
+ // }
+ // }
if ((tempWidget != NULL) && tempVisible)
{
@@ -520,7 +617,7 @@ QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES t
void MainWindow::closeEvent(QCloseEvent *event)
{
- //settings.setValue("geometry", saveGeometry());
+ settings.setValue("geometry", saveGeometry());
//settings.setValue("windowState", saveState());
aboutToCloseFlag = true;
settings.setValue("VIEW_ON_APPLICATION_CLOSE", currentView);
@@ -528,14 +625,13 @@ void MainWindow::closeEvent(QCloseEvent *event)
QMainWindow::closeEvent(event);
}
+/**
+ * Stores the visibility setting of each widget. This method
+ * will only change the settings if the application is not
+ * about to close.
+ */
void MainWindow::updateVisibilitySettings (bool vis)
{
- // This is commented since when the application closes
- // sets the visibility to false.
-
- // TODO: A workaround is needed. The QApplication::aboutToQuit
- // did not work
-
if (!aboutToCloseFlag)
{
@@ -549,10 +645,9 @@ void MainWindow::updateVisibilitySettings (bool vis)
i.next();
if ((static_cast (dockWidgets[i.key()])) == temp)
{
-// QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.key()), currentView);
-// qDebug() << "Key in visibility changed" << chKey;
-// settings.setValue(chKey,vis);
-// settings.sync();
+ QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.key()), currentView);
+ settings.setValue(chKey,vis);
+ settings.sync();
toolsMenuActions[i.key()]->setChecked(vis);
break;
}
@@ -628,8 +723,8 @@ void MainWindow::arrangeCommonCenterStack()
if (!centerStack) return;
- if (mapWidget) centerStack->addWidget(mapWidget);
- if (protocolWidget) centerStack->addWidget(protocolWidget);
+ if (mapWidget && (centerStack->indexOf(mapWidget) == -1)) centerStack->addWidget(mapWidget);
+ if (protocolWidget && (centerStack->indexOf(protocolWidget) == -1)) centerStack->addWidget(protocolWidget);
setCentralWidget(centerStack);
}
@@ -642,20 +737,20 @@ void MainWindow::arrangePxCenterStack()
return;
}
- if (linechartWidget) centerStack->addWidget(linechartWidget);
+
+ if (linechartWidget && (centerStack->indexOf(linechartWidget) == -1)) centerStack->addWidget(linechartWidget);
#ifdef QGC_OSG_ENABLED
- if (_3DWidget) centerStack->addWidget(_3DWidget);
+ if (_3DWidget && (centerStack->indexOf(_3DWidget) == -1)) centerStack->addWidget(_3DWidget);
#endif
#ifdef QGC_OSGEARTH_ENABLED
- if (_3DMapWidget) centerStack->addWidget(_3DMapWidget);
+ if (_3DMapWidget && (centerStack->indexOf(_3DMapWidget) == -1)) centerStack->addWidget(_3DMapWidget);
#endif
#if (defined _MSC_VER) | (defined Q_OS_MAC)
- if (gEarthWidget) centerStack->addWidget(gEarthWidget);
+ if (gEarthWidget && (centerStack->indexOf(gEarthWidget) == -1)) centerStack->addWidget(gEarthWidget);
#endif
- if (hudWidget) centerStack->addWidget(hudWidget);
- if (dataplotWidget) centerStack->addWidget(dataplotWidget);
-
+ if (hudWidget && (centerStack->indexOf(hudWidget) == -1)) centerStack->addWidget(hudWidget);
+ if (dataplotWidget && (centerStack->indexOf(dataplotWidget) == -1)) centerStack->addWidget(dataplotWidget);
}
void MainWindow::arrangeSlugsCenterStack()
@@ -666,8 +761,8 @@ void MainWindow::arrangeSlugsCenterStack()
return;
}
- if (linechartWidget) centerStack->addWidget(linechartWidget);
- if (hudWidget) centerStack->addWidget(hudWidget);
+ if (linechartWidget && (centerStack->indexOf(linechartWidget) == -1)) centerStack->addWidget(linechartWidget);
+ if (hudWidget && (centerStack->indexOf(hudWidget) == -1)) centerStack->addWidget(hudWidget);
}
@@ -1204,52 +1299,52 @@ void MainWindow::presentView()
// HORIZONTAL SITUATION INDICATOR
showTheWidget(MENU_HSI, currentView);
-// if (hsiDockWidget)
-// {
-// HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() );
-// if (hsi){
-// if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
-// addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
-// hsiDockWidget);
-// }
-// }
-// }
+ // if (hsiDockWidget)
+ // {
+ // HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() );
+ // if (hsi){
+ // if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
+ // addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
+ // hsiDockWidget);
+ // }
+ // }
+ // }
// HEAD DOWN 1
showTheWidget(MENU_HDD_1, currentView);
-// if (headDown1DockWidget)
-// {
-// HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget());
-// if (hdd) {
-// if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool()) {
-// addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
-// headDown1DockWidget);
-// headDown1DockWidget->show();
-// hdd->start();
-// } else {
-// headDown1DockWidget->hide();;
-// hdd->stop();
-// }
-// }
-// }
+ // if (headDown1DockWidget)
+ // {
+ // HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget());
+ // if (hdd) {
+ // if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool()) {
+ // addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
+ // headDown1DockWidget);
+ // headDown1DockWidget->show();
+ // hdd->start();
+ // } else {
+ // headDown1DockWidget->hide();;
+ // hdd->stop();
+ // }
+ // }
+ // }
// HEAD DOWN 2
showTheWidget(MENU_HDD_2, currentView);
-// if (headDown2DockWidget)
-// {
-// HDDisplay *hdd = dynamic_cast(headDown2DockWidget->widget());
-// if (hdd){
-// if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool()){
-// addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
-// headDown2DockWidget);
-// headDown2DockWidget->show();
-// hdd->start();
-// } else {
-// headDown2DockWidget->hide();
-// hdd->stop();
-// }
-// }
-// }
+ // if (headDown2DockWidget)
+ // {
+ // HDDisplay *hdd = dynamic_cast(headDown2DockWidget->widget());
+ // if (hdd){
+ // if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool()){
+ // addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
+ // headDown2DockWidget);
+ // headDown2DockWidget->show();
+ // hdd->start();
+ // } else {
+ // headDown2DockWidget->hide();
+ // hdd->stop();
+ // }
+ // }
+ // }
this->show();
@@ -1280,23 +1375,8 @@ void MainWindow::loadWidgets()
//loadPilotView();
}
-void MainWindow::loadDataView()
-{
- clearView();
-
- // DATAPLOT
- if (dataplotWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- centerStack->setCurrentWidget(dataplotWidget);
- }
-}
-
void MainWindow::loadDataView(QString fileName)
{
- clearView();
-
// DATAPLOT
if (dataplotWidget)
{
diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h
index 01c6fe17581c70910c77dabaf59f7b2283154c31..f866e9a1c6339a393d75d920c39ac639f6a996af 100644
--- a/src/ui/MainWindow.h
+++ b/src/ui/MainWindow.h
@@ -63,7 +63,9 @@ This file is part of the QGROUNDCONTROL project
#include "HSIDisplay.h"
#include "QGCDataPlot2D.h"
#include "QGCRemoteControlView.h"
+#if (defined Q_OS_MAC) | (defined _MSC_VER)
#include "QGCGoogleEarthView.h"
+#endif
//#include "QMap3DWidget.h"
#include "SlugsDataSensorView.h"
#include "LogCompressor.h"
@@ -148,8 +150,6 @@ public slots:
void loadWidgets();
- /** @brief Load data view, allowing to plot flight data */
- void loadDataView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
diff --git a/src/ui/ObjectDetectionView.cc b/src/ui/ObjectDetectionView.cc
index 922a1c61562365f7dec4c6acd273f214d6207546..b070795f01ab598471a564030fab3807e60848ea 100644
--- a/src/ui/ObjectDetectionView.cc
+++ b/src/ui/ObjectDetectionView.cc
@@ -77,12 +77,15 @@ void ObjectDetectionView::changeEvent(QEvent *e)
void ObjectDetectionView::setUAS(UASInterface* uas)
{
- //if (this->uas == NULL && uas != NULL)
- //{
+ if (this->uas != NULL)
+ {
+ disconnect(this->uas, SIGNAL(patternDetected(int, QString, float, bool)), this, SLOT(newPattern(int, QString, float, bool)));
+ disconnect(this->uas, SIGNAL(letterDetected(int, QString, float, bool)), this, SLOT(newLetter(int, QString, float, bool)));
+ }
+
this->uas = uas;
connect(uas, SIGNAL(patternDetected(int, QString, float, bool)), this, SLOT(newPattern(int, QString, float, bool)));
connect(uas, SIGNAL(letterDetected(int, QString, float, bool)), this, SLOT(newLetter(int, QString, float, bool)));
- //}
}
void ObjectDetectionView::newPattern(int uasId, QString patternPath, float confidence, bool detected)
diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc
index afaf40dae0f1dd67b489f584861e5bfb0775116c..6f71b0ba4bffcef163e9765ea4584919162f5386 100644
--- a/src/ui/QGCDataPlot2D.cc
+++ b/src/ui/QGCDataPlot2D.cc
@@ -126,6 +126,13 @@ void QGCDataPlot2D::savePlot()
fileName = QFileDialog::getSaveFileName(
this, "Export File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
"PDF Documents (*.pdf);;SVG Images (*.svg)");
+
+ if (!fileName.contains("."))
+ {
+ // .csv is default extension
+ fileName.append(".pdf");
+ }
+
while(!(fileName.endsWith(".svg") || fileName.endsWith(".pdf")))
{
QMessageBox msgBox;
@@ -262,7 +269,7 @@ void QGCDataPlot2D::selectFile()
// Let user select the log file name
//QDate date(QDate::currentDate());
// QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
- fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), tr("."), tr("Logfile (*.txt)"));
+ fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), QString(), "Logfile (*.csv *.txt *.log)");
// Store reference to file
QFileInfo fileInfo(fileName);
diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc
index ef4ad51cf4dbb1d4b464d9d7dd2882ab7098cc63..7fef09c2b92995fc31440a23bfcccb920769cbfe 100644
--- a/src/ui/QGCParamWidget.cc
+++ b/src/ui/QGCParamWidget.cc
@@ -62,26 +62,38 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
horizontalLayout->addWidget(tree, 0, 0, 1, 3);
QPushButton* refreshButton = new QPushButton(tr("Refresh"));
+ refreshButton->setToolTip(tr("Load parameters currently in non-permanent memory of aircraft."));
+ refreshButton->setWhatsThis(tr("Load parameters currently in non-permanent memory of aircraft."));
connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestParameterList()));
horizontalLayout->addWidget(refreshButton, 1, 0);
QPushButton* setButton = new QPushButton(tr("Transmit"));
+ setButton->setToolTip(tr("Set current parameters in non-permanent onboard memory"));
+ setButton->setWhatsThis(tr("Set current parameters in non-permanent onboard memory"));
connect(setButton, SIGNAL(clicked()), this, SLOT(setParameters()));
horizontalLayout->addWidget(setButton, 1, 1);
QPushButton* writeButton = new QPushButton(tr("Write (ROM)"));
+ writeButton->setToolTip(tr("Copy current parameters in non-permanent memory of the aircraft to permanent memory. Transmit your parameters first to write these."));
+ writeButton->setWhatsThis(tr("Copy current parameters in non-permanent memory of the aircraft to permanent memory. Transmit your parameters first to write these."));
connect(writeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
horizontalLayout->addWidget(writeButton, 1, 2);
QPushButton* readButton = new QPushButton(tr("Read (ROM)"));
+ readButton->setToolTip(tr("Copy parameters from permanent memory to non-permanent current memory of aircraft. DOES NOT update the parameters in this view, click refresh after copying them to get them."));
+ readButton->setWhatsThis(tr("Copy parameters from permanent memory to non-permanent current memory of aircraft. DOES NOT update the parameters in this view, click refresh after copying them to get them."));
connect(readButton, SIGNAL(clicked()), this, SLOT(readParameters()));
horizontalLayout->addWidget(readButton, 2, 2);
QPushButton* loadFileButton = new QPushButton(tr("Load File"));
+ loadFileButton->setToolTip(tr("Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them."));
+ loadFileButton->setWhatsThis(tr("Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them."));
connect(loadFileButton, SIGNAL(clicked()), this, SLOT(loadParameters()));
horizontalLayout->addWidget(loadFileButton, 2, 0);
QPushButton* saveFileButton = new QPushButton(tr("Save File"));
+ saveFileButton->setToolTip(tr("Save parameters in this view to a file on this computer."));
+ saveFileButton->setWhatsThis(tr("Save parameters in this view to a file on this computer."));
connect(saveFileButton, SIGNAL(clicked()), this, SLOT(saveParameters()));
horizontalLayout->addWidget(saveFileButton, 2, 1);
diff --git a/src/ui/SerialConfigurationWindow.h b/src/ui/SerialConfigurationWindow.h
index abfa5c138c0ea3ba8ffb5e7c118ff26ab2ce86c5..69b020182a8fd20df7108d74731c27327b69ba04 100644
--- a/src/ui/SerialConfigurationWindow.h
+++ b/src/ui/SerialConfigurationWindow.h
@@ -62,11 +62,9 @@ public slots:
void setLinkName(QString name);
void setupPortList();
-protected slots:
+protected:
void showEvent(QShowEvent* event);
void hideEvent(QHideEvent* event);
-
-protected:
bool userConfigured; ///< Switch to detect if current values are user-selected and shouldn't be overriden
private:
diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc
index 3a7cb0183279d73dc87ff51d98e2f9bea52e1f3c..9532b1ce970f1dd06f00fb034207bdb26ea2d7e0 100644
--- a/src/ui/linechart/LinechartPlot.cc
+++ b/src/ui/linechart/LinechartPlot.cc
@@ -43,6 +43,8 @@ This file is part of the PIXHAWK project
#include
#include
+#include "QGC.h"
+
/**
* @brief The default constructor
*
@@ -55,7 +57,7 @@ maxTime(QUINT64_MIN),
maxInterval(MAX_STORAGE_INTERVAL),
timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds
automaticScrollActive(false),
-m_active(true),
+m_active(false),
m_groundTime(true),
d_data(NULL),
d_curve(NULL)
@@ -142,7 +144,7 @@ d_curve(NULL)
// Start QTimer for plot update
updateTimer = new QTimer(this);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(paintRealtime()));
- updateTimer->start(DEFAULT_REFRESH_RATE);
+ //updateTimer->start(DEFAULT_REFRESH_RATE);
// QwtPlot::setAutoReplot();
@@ -155,6 +157,18 @@ LinechartPlot::~LinechartPlot()
removeAllData();
}
+void LinechartPlot::showEvent(QShowEvent* event)
+{
+ Q_UNUSED(event);
+ updateTimer->start(DEFAULT_REFRESH_RATE);
+}
+
+void LinechartPlot::hideEvent(QHideEvent* event)
+{
+ Q_UNUSED(event);
+ updateTimer->stop();
+}
+
int LinechartPlot::getPlotId()
{
return this->plotid;
@@ -184,6 +198,14 @@ double LinechartPlot::getMedian(QString id)
return data.value(id)->getMedian();
}
+/**
+ * @param id curve identifier
+ */
+double LinechartPlot::getVariance(QString id)
+{
+ return data.value(id)->getVariance();
+}
+
int LinechartPlot::getAverageWindow()
{
return averageWindowSize;
@@ -272,6 +294,14 @@ void LinechartPlot::enforceGroundTime(bool enforce)
m_groundTime = enforce;
}
+/**
+ * @return True if the data points are stamped with the packet receive time
+ */
+bool LinechartPlot::groundTime()
+{
+ return m_groundTime;
+}
+
void LinechartPlot::addCurve(QString id)
{
QColor currentColor = getNextColor();
@@ -454,6 +484,23 @@ bool LinechartPlot::isVisible(QString id)
return curves.value(id)->isVisible();
}
+/**
+ * @return The visibility, true if it is visible, false otherwise
+ **/
+bool LinechartPlot::anyCurveVisible()
+{
+ bool visible = false;
+ foreach (QString key, curves.keys())
+ {
+ if (curves.value(key)->isVisible())
+ {
+ visible = true;
+ }
+ }
+
+ return visible;
+}
+
/**
* @brief Allows to block interference of the automatic scrolling with user interaction
* When the plot is updated very fast (at 1 ms for example) with new data, it might
@@ -580,6 +627,9 @@ void LinechartPlot::paintRealtime()
{
if (m_active)
{
+#if (QGC_EVENTLOOP_DEBUG)
+ qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
+#endif
// Update plot window value to new max time if the last time was also the max time
windowLock.lock();
if (automaticScrollActive)
@@ -701,8 +751,9 @@ TimeSeriesData::TimeSeriesData(QwtPlot* plot, QString friendlyName, quint64 plot
maxValue(DBL_MIN),
zeroValue(0),
count(0),
- mean(0.00),
- median(0.00),
+ mean(0.0),
+ median(0.0),
+ variance(0.0),
averageWindow(50)
{
this->plot = plot;
@@ -760,6 +811,14 @@ void TimeSeriesData::append(quint64 ms, double value)
medianList.append(this->value[count-i]);
}
mean = mean / static_cast(qMin(averageWindow,static_cast(count)));
+
+ this->variance = 0;
+ for (unsigned int i = 0; (i < averageWindow) && (((int)count - (int)i) >= 0); ++i)
+ {
+ this->variance += (this->value[count-i] - mean) * (this->value[count-i] - mean);
+ }
+ this->variance = this->variance / static_cast(qMin(averageWindow,static_cast(count)));
+
qSort(medianList);
if (medianList.count() > 2)
@@ -859,6 +918,14 @@ double TimeSeriesData::getMedian()
return median;
}
+/**
+ * @return the variance
+ */
+double TimeSeriesData::getVariance()
+{
+ return variance;
+}
+
double TimeSeriesData::getCurrentValue()
{
return lastValue;
diff --git a/src/ui/linechart/LinechartPlot.h b/src/ui/linechart/LinechartPlot.h
index 138df19195ddcf693e6cf351b4a10a8a45f59264..a180135219ec40c4dc732889340b74cad98089bc 100644
--- a/src/ui/linechart/LinechartPlot.h
+++ b/src/ui/linechart/LinechartPlot.h
@@ -132,6 +132,8 @@ public:
double getMean();
/** @brief Get the short-term median */
double getMedian();
+ /** @brief Get the short-term variance */
+ double getVariance();
/** @brief Get the current value */
double getCurrentValue();
void setZeroValue(double zeroValue);
@@ -166,6 +168,7 @@ private:
QwtArray value;
double mean;
double median;
+ double variance;
unsigned int averageWindow;
QwtArray outputMs;
QwtArray outputValue;
@@ -190,6 +193,8 @@ public:
QList getCurves();
bool isVisible(QString id);
+ /** @brief Check if any curve is visible */
+ bool anyCurveVisible();
int getPlotId();
/** @brief Get the number of values to average over */
@@ -206,6 +211,8 @@ public:
double getMean(QString id);
/** @brief Get the short-term median of a curve */
double getMedian(QString id);
+ /** @brief Get the short-term variance of a curve */
+ double getVariance(QString id);
/** @brief Get the last inserted value */
double getCurrentValue(QString id);
@@ -214,8 +221,8 @@ public:
static const int SCALE_LOGARITHMIC = 2;
static const int DEFAULT_REFRESH_RATE = 50; ///< The default refresh rate is 25 Hz / every 100 ms
- static const int DEFAULT_PLOT_INTERVAL = 1000 * 12; ///< The default plot interval is 15 seconds
- static const int DEFAULT_SCALE_INTERVAL = 1000 * 5;
+ static const int DEFAULT_PLOT_INTERVAL = 1000 * 8; ///< The default plot interval is 15 seconds
+ static const int DEFAULT_SCALE_INTERVAL = 1000 * 8;
public slots:
void setRefreshRate(int ms);
@@ -243,6 +250,8 @@ public slots:
/** @brief Enforce the use of the receive timestamp */
void enforceGroundTime(bool enforce);
+ /** @brief Check if the receive timestamp is enforced */
+ bool groundTime();
// General interaction
void setWindowPosition(quint64 end);
@@ -301,6 +310,8 @@ protected:
// Methods
void addCurve(QString id);
QColor getNextColor();
+ void showEvent(QShowEvent* event);
+ void hideEvent(QHideEvent* event);
private:
TimeSeriesData* d_data;
diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc
index 03153e9acb6537b96bf75b740521664f92022058..d1703573e3fc178fa9c7db3b8276e4281aeb21e6 100644
--- a/src/ui/linechart/LinechartWidget.cc
+++ b/src/ui/linechart/LinechartWidget.cc
@@ -48,6 +48,7 @@ This file is part of the PIXHAWK project
#include "LinechartWidget.h"
#include "LinechartPlot.h"
#include "LogCompressor.h"
+#include "QGC.h"
#include "MG.h"
@@ -62,6 +63,7 @@ listedCurves(new QList()),
curveLabels(new QMap()),
curveMeans(new QMap()),
curveMedians(new QMap()),
+curveVariances(new QMap()),
curveMenu(new QMenu(this)),
logFile(new QFile()),
logindex(1),
@@ -79,16 +81,52 @@ updateTimer(new QTimer())
curvesWidgetLayout->setMargin(2);
curvesWidgetLayout->setSpacing(4);
curvesWidgetLayout->setSizeConstraint(QLayout::SetMinimumSize);
+ curvesWidgetLayout->setAlignment(Qt::AlignTop);
curvesWidget->setLayout(curvesWidgetLayout);
+ // Create curve list headings
+ QWidget* form = new QWidget(this);
+ QHBoxLayout *horizontalLayout;
+ QLabel* label;
+ QLabel* value;
+ QLabel* mean;
+ QLabel* variance;
+ form->setAutoFillBackground(false);
+ horizontalLayout = new QHBoxLayout(form);
+ horizontalLayout->setSpacing(5);
+ horizontalLayout->setMargin(0);
+ horizontalLayout->setSizeConstraint(QLayout::SetMinimumSize);
+
+ //horizontalLayout->addWidget(checkBox);
+
+ label = new QLabel(form);
+ label->setText("Name");
+ horizontalLayout->addWidget(label);
+
+ // Value
+ value = new QLabel(form);
+ value->setText("Val");
+ horizontalLayout->addWidget(value);
+
+ // Mean
+ mean = new QLabel(form);
+ mean->setText("Mean");
+ horizontalLayout->addWidget(mean);
+
+ // Variance
+ variance = new QLabel(form);
+ variance->setText("Variance");
+ horizontalLayout->addWidget(variance);
+ curvesWidgetLayout->addWidget(form);
+
// Add and customize plot elements (right side)
// Create the layout
createLayout();
// Add the last actions
- connect(this, SIGNAL(plotWindowPositionUpdated(int)), scrollbar, SLOT(setValue(int)));
- connect(scrollbar, SIGNAL(sliderMoved(int)), this, SLOT(setPlotWindowPosition(int)));
+ //connect(this, SIGNAL(plotWindowPositionUpdated(int)), scrollbar, SLOT(setValue(int)));
+ //connect(scrollbar, SIGNAL(sliderMoved(int)), this, SLOT(setPlotWindowPosition(int)));
updateTimer->setInterval(300);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
@@ -129,6 +167,8 @@ void LinechartWidget::createLayout()
scalingLinearButton = createButton(this);
scalingLinearButton->setDefaultAction(setScalingLinear);
scalingLinearButton->setCheckable(true);
+ scalingLinearButton->setToolTip(tr("Set linear scale for Y axis"));
+ scalingLinearButton->setWhatsThis(tr("Set linear scale for Y axis"));
layout->addWidget(scalingLinearButton, 1, 0);
layout->setColumnStretch(0, 0);
@@ -136,13 +176,18 @@ void LinechartWidget::createLayout()
scalingLogButton = createButton(this);
scalingLogButton->setDefaultAction(setScalingLogarithmic);
scalingLogButton->setCheckable(true);
+ scalingLogButton->setToolTip(tr("Set logarithmic scale for Y axis"));
+ scalingLogButton->setWhatsThis(tr("Set logarithmic scale for Y axis"));
layout->addWidget(scalingLogButton, 1, 1);
layout->setColumnStretch(1, 0);
// Averaging spin box
averageSpinBox = new QSpinBox(this);
- averageSpinBox->setValue(200);
+ averageSpinBox->setToolTip(tr("Sliding window size to calculate mean and variance"));
+ averageSpinBox->setWhatsThis(tr("Sliding window size to calculate mean and variance"));
averageSpinBox->setMinimum(2);
+ averageSpinBox->setValue(200);
+ setAverageWindow(200);
averageSpinBox->setMaximum(9999);
layout->addWidget(averageSpinBox, 1, 2);
layout->setColumnStretch(2, 0);
@@ -150,6 +195,8 @@ void LinechartWidget::createLayout()
// Log Button
logButton = new QToolButton(this);
+ logButton->setToolTip(tr("Start to log curve data into a CSV or TXT file"));
+ logButton->setWhatsThis(tr("Start to log curve data into a CSV or TXT file"));
logButton->setText(tr("Start Logging"));
layout->addWidget(logButton, 1, 3);
layout->setColumnStretch(3, 0);
@@ -159,6 +206,8 @@ void LinechartWidget::createLayout()
QToolButton* timeButton = new QToolButton(this);
timeButton->setText(tr("Ground Time"));
timeButton->setCheckable(true);
+ timeButton->setToolTip(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
+ timeButton->setWhatsThis(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
bool gTimeDefault = true;
if (activePlot) activePlot->enforceGroundTime(gTimeDefault);
timeButton->setChecked(gTimeDefault);
@@ -167,18 +216,18 @@ void LinechartWidget::createLayout()
connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool)));
// Create the scroll bar
- scrollbar = new QScrollBar(Qt::Horizontal, ui.diagramGroupBox);
- scrollbar->setMinimum(MIN_TIME_SCROLLBAR_VALUE);
- scrollbar->setMaximum(MAX_TIME_SCROLLBAR_VALUE);
- scrollbar->setPageStep(PAGESTEP_TIME_SCROLLBAR_VALUE);
+ //scrollbar = new QScrollBar(Qt::Horizontal, ui.diagramGroupBox);
+ //scrollbar->setMinimum(MIN_TIME_SCROLLBAR_VALUE);
+ //scrollbar->setMaximum(MAX_TIME_SCROLLBAR_VALUE);
+ //scrollbar->setPageStep(PAGESTEP_TIME_SCROLLBAR_VALUE);
// Set scrollbar to maximum and disable it
- scrollbar->setValue(MIN_TIME_SCROLLBAR_VALUE);
- scrollbar->setDisabled(true);
+ //scrollbar->setValue(MIN_TIME_SCROLLBAR_VALUE);
+ //scrollbar->setDisabled(true);
// scrollbar->setFixedHeight(20);
// Add scroll bar to layout and make sure it gets all available space
- layout->addWidget(scrollbar, 1, 5);
+ //layout->addWidget(scrollbar, 1, 5);
layout->setColumnStretch(5, 10);
ui.diagramGroupBox->setLayout(layout);
@@ -225,7 +274,18 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
{
if (activePlot->isVisible(curve))
{
- logFile->write(QString(QString::number(usec) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1());
+ quint64 time = 0;
+ // Adjust time
+ if (activePlot->groundTime())
+ {
+ time = QGC::groundTimeUsecs() - logStartTime;
+ }
+ else
+ {
+ time = usec - logStartTime;
+ }
+
+ logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1());
logFile->flush();
}
}
@@ -256,19 +316,47 @@ void LinechartWidget::refresh()
// str.sprintf("%+.2f", activePlot->getMedian(k.key()));
// k.value()->setText(str);
// }
+ QMap::iterator l;
+ for (l = curveVariances->begin(); l != curveVariances->end(); ++l)
+ {
+ // Variance
+ str.sprintf("%+.5f", activePlot->getVariance(l.key()));
+ l.value()->setText(str);
+ }
}
void LinechartWidget::startLogging()
{
- // Let user select the log file name
- QDate date(QDate::currentDate());
- // QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
- QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.txt, *.csv);;"));
// Store reference to file
// Append correct file ending if needed
bool abort = false;
- while (!(fileName.endsWith(".txt") || fileName.endsWith(".csv")))
+
+ // Check if any curve is enabled
+ if (!activePlot->anyCurveVisible())
+ {
+ QMessageBox msgBox;
+ msgBox.setIcon(QMessageBox::Critical);
+ msgBox.setText("No curves selected for logging.");
+ msgBox.setInformativeText("Please check all curves you want to log. Currently no data would be logged, aborting the logging.");
+ msgBox.setStandardButtons(QMessageBox::Ok);
+ msgBox.setDefaultButton(QMessageBox::Ok);
+ msgBox.exec();
+ return;
+ }
+
+ // Let user select the log file name
+ QDate date(QDate::currentDate());
+ // QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
+ QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.csv, *.txt);;"));
+
+ if (!fileName.contains("."))
+ {
+ // .csv is default extension
+ fileName.append(".csv");
+ }
+
+ while (!(fileName.endsWith(".txt") || fileName.endsWith(".csv")) && !abort)
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
@@ -292,6 +380,7 @@ void LinechartWidget::startLogging()
if (logFile->open(QIODevice::WriteOnly | QIODevice::Text))
{
logging = true;
+ logStartTime = QGC::groundTimeUsecs();
logindex++;
logButton->setText(tr("Stop logging"));
disconnect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
@@ -354,6 +443,7 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
QLabel* label;
QLabel* value;
QLabel* mean;
+ QLabel* variance;
form->setAutoFillBackground(false);
horizontalLayout = new QHBoxLayout(form);
horizontalLayout->setSpacing(5);
@@ -363,6 +453,8 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
checkBox = new QCheckBox(form);
checkBox->setCheckable(true);
checkBox->setObjectName(curve);
+ checkBox->setToolTip(tr("Enable the curve in the graph window"));
+ checkBox->setWhatsThis(tr("Enable the curve in the graph window"));
horizontalLayout->addWidget(checkBox);
@@ -388,12 +480,16 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
// Value
value = new QLabel(form);
value->setNum(0.00);
+ value->setToolTip(tr("Current value of ") + curve);
+ value->setWhatsThis(tr("Current value of ") + curve);
curveLabels->insert(curve, value);
horizontalLayout->addWidget(value);
// Mean
mean = new QLabel(form);
mean->setNum(0.00);
+ mean->setToolTip(tr("Arithmetic mean of ") + curve);
+ mean->setWhatsThis(tr("Arithmetic mean of ") + curve);
curveMeans->insert(curve, mean);
horizontalLayout->addWidget(mean);
@@ -403,6 +499,14 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
// curveMedians->insert(curve, median);
// horizontalLayout->addWidget(median);
+ // Variance
+ variance = new QLabel(form);
+ variance->setNum(0.00);
+ variance->setToolTip(tr("Variance of ") + curve);
+ variance->setWhatsThis(tr("Variance of ") + curve);
+ curveVariances->insert(curve, variance);
+ horizontalLayout->addWidget(variance);
+
/* Color picker
QColor color = QColorDialog::getColor(Qt::green, this);
if (color.isValid()) {
@@ -419,6 +523,7 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
horizontalLayout->setStretchFactor(value, 50);
horizontalLayout->setStretchFactor(mean, 50);
// horizontalLayout->setStretchFactor(median, 50);
+ horizontalLayout->setStretchFactor(variance, 50);
// Connect actions
QObject::connect(checkBox, SIGNAL(clicked(bool)), this, SLOT(takeButtonClick(bool)));
@@ -447,7 +552,13 @@ void LinechartWidget::removeCurve(QString curve)
void LinechartWidget::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
- setActive(isVisible());
+ setActive(true);
+}
+
+void LinechartWidget::hideEvent(QHideEvent* event)
+{
+ Q_UNUSED(event);
+ setActive(false);
}
void LinechartWidget::setActive(bool active)
@@ -528,14 +639,14 @@ void LinechartWidget::setPlotWindowPosition(quint64 position) {
// A relative position makes only sense if the plot is filled
if(activePlot->getDataInterval() > activePlot->getPlotInterval()) {
//TODO @todo Implement the scrollbar enabling in a more elegant way
- scrollbar->setDisabled(false);
+ //scrollbar->setDisabled(false);
quint64 scrollInterval = position - activePlot->getMinTime() - activePlot->getPlotInterval();
pos = (static_cast(scrollInterval) / (activePlot->getDataInterval() - activePlot->getPlotInterval()));
} else {
- scrollbar->setDisabled(true);
+ //scrollbar->setDisabled(true);
pos = 1;
}
plotWindowLock.unlock();
@@ -551,7 +662,8 @@ void LinechartWidget::setPlotWindowPosition(quint64 position) {
*
* @param interval The time interval to plot
**/
-void LinechartWidget::setPlotInterval(quint64 interval) {
+void LinechartWidget::setPlotInterval(quint64 interval)
+{
activePlot->setPlotInterval(interval);
}
@@ -562,7 +674,8 @@ void LinechartWidget::setPlotInterval(quint64 interval) {
*
* @param checked The visibility of the curve: true to display the curve, false otherwise
**/
-void LinechartWidget::takeButtonClick(bool checked) {
+void LinechartWidget::takeButtonClick(bool checked)
+{
QCheckBox* button = qobject_cast(QObject::sender());
@@ -579,7 +692,8 @@ void LinechartWidget::takeButtonClick(bool checked) {
* @param text The button text
* @param parent The parent object (to ensure that the memory is freed after the deletion of the button)
**/
-QToolButton* LinechartWidget::createButton(QWidget* parent) {
+QToolButton* LinechartWidget::createButton(QWidget* parent)
+{
QToolButton* button = new QToolButton(parent);
button->setMinimumSize(QSize(20, 20));
button->setMaximumSize(60, 20);
diff --git a/src/ui/linechart/LinechartWidget.h b/src/ui/linechart/LinechartWidget.h
index 7256760b17ecf2962d1227bce0bd486fb4927512..d14269c6dd472779d1dc287904f6a566fb756f76 100644
--- a/src/ui/linechart/LinechartWidget.h
+++ b/src/ui/linechart/LinechartWidget.h
@@ -77,8 +77,10 @@ public slots:
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
void setPlotInterval(quint64 interval);
- /** @brief Override base class show */
- virtual void showEvent(QShowEvent* event);
+ /** @brief Start automatic updates once visible */
+ void showEvent(QShowEvent* event);
+ /** @brief Stop automatic updates once hidden */
+ void hideEvent(QHideEvent* event);
void setActive(bool active);
/** @brief Set the number of values to average over */
void setAverageWindow(int windowSize);
@@ -107,6 +109,7 @@ protected:
QMap* curveLabels; ///< References to the curve labels
QMap* curveMeans; ///< References to the curve means
QMap* curveMedians; ///< References to the curve medians
+ QMap* curveVariances; ///< References to the curve variances
QWidget* curvesWidget; ///< The QWidget containing the curve selection button
QVBoxLayout* curvesWidgetLayout; ///< The layout for the curvesWidget QWidget
@@ -129,6 +132,7 @@ protected:
bool logging;
QTimer* updateTimer;
LogCompressor* compressor;
+ quint64 logStartTime;
static const int MAX_CURVE_MENUITEM_NUMBER = 8;
static const int PAGESTEP_TIME_SCROLLBAR_VALUE = (MAX_TIME_SCROLLBAR_VALUE - MIN_TIME_SCROLLBAR_VALUE) / 10;
diff --git a/src/ui/linechart/Linecharts.cc b/src/ui/linechart/Linecharts.cc
index 4bf4cc401f0242b962b4291ae8db4147b6778d5e..aba663f58159953e6962d899abe421c7defad9bc 100644
--- a/src/ui/linechart/Linecharts.cc
+++ b/src/ui/linechart/Linecharts.cc
@@ -10,28 +10,47 @@ Linecharts::Linecharts(QWidget *parent) :
plots(),
active(true)
{
- this->setVisible(false);
- // Get current MAV list
- QList systems = UASManager::instance()->getUASList();
+ this->setVisible(false);
+ // Get current MAV list
+ QList systems = UASManager::instance()->getUASList();
- // Add each of them
- foreach (UASInterface* sys, systems)
- {
- addSystem(sys);
- }
- connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
- this, SLOT(addSystem(UASInterface*)));
- connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
- this, SLOT(selectSystem(int)));
- connect(this, SIGNAL(logfileWritten(QString)),
- MainWindow::instance(), SLOT(loadDataView(QString)));
+ // Add each of them
+ foreach (UASInterface* sys, systems)
+ {
+ addSystem(sys);
+ }
+ connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
+ this, SLOT(addSystem(UASInterface*)));
+ connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
+ this, SLOT(selectSystem(int)));
+ connect(this, SIGNAL(logfileWritten(QString)),
+ MainWindow::instance(), SLOT(loadDataView(QString)));
}
void Linecharts::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
- if (!event->spontaneous())
+ Q_UNUSED(event)
+ {
+ QWidget* prevWidget = currentWidget();
+ if (prevWidget)
+ {
+ LinechartWidget* chart = dynamic_cast(prevWidget);
+ if (chart)
+ {
+ this->active = true;
+ chart->setActive(true);
+ }
+ }
+ }
+}
+
+void Linecharts::hideEvent(QHideEvent* event)
+{
+ // React only to internal (pre-display)
+ // events
+ Q_UNUSED(event)
{
QWidget* prevWidget = currentWidget();
if (prevWidget)
@@ -39,16 +58,8 @@ void Linecharts::showEvent(QShowEvent* event)
LinechartWidget* chart = dynamic_cast(prevWidget);
if (chart)
{
- if (event->type() == QEvent::Hide)
- {
- this->active = false;
- chart->setActive(false);
- }
- else if (event->type() == QEvent::Show)
- {
- this->active = true;
- chart->setActive(true);
- }
+ this->active = false;
+ chart->setActive(false);
}
}
}
diff --git a/src/ui/linechart/Linecharts.h b/src/ui/linechart/Linecharts.h
index 91e058b7d37b5188c58358417c945ce70cbf55d1..99fb44e9f71630b398162fec025c872baf2e0da0 100644
--- a/src/ui/linechart/Linecharts.h
+++ b/src/ui/linechart/Linecharts.h
@@ -26,8 +26,10 @@ public slots:
protected:
QMap plots;
bool active;
-
+ /** @brief Start updating widget */
void showEvent(QShowEvent* event);
+ /** @brief Stop updating widget */
+ void hideEvent(QHideEvent* event);
};
diff --git a/src/ui/map3D/Q3DWidget.cc b/src/ui/map3D/Q3DWidget.cc
index 2712799b7c08dd77f2ba93f3ed761ab5d4345b9e..8e3f3b4988e86b75c8c21ed388cd133f2f68251a 100644
--- a/src/ui/map3D/Q3DWidget.cc
+++ b/src/ui/map3D/Q3DWidget.cc
@@ -30,6 +30,7 @@ This file is part of the QGROUNDCONTROL project
*/
#include "Q3DWidget.h"
+#include "QGC.h"
#include
#include
@@ -105,24 +106,23 @@ Q3DWidget::init(float fps)
cameraManipulator->setDistance(cameraParams.minZoomRange * 2.0);
connect(&timer, SIGNAL(timeout()), this, SLOT(redraw()));
- timer.start(static_cast(floorf(1000.0f / fps)));
+ // DO NOT START TIMER IN INITIALIZATION! IT IS STARTED IN THE SHOW EVENT
}
void Q3DWidget::showEvent(QShowEvent* event)
{
// React only to internal (pre/post-display)
// events
- if (!event->spontaneous())
- {
- if (event->type() == QEvent::Hide)
- {
- timer.stop();
- }
- else if (event->type() == QEvent::Show)
- {
- timer.start(static_cast(floorf(1000.0f / fps)));
- }
- }
+ Q_UNUSED(event)
+ timer.start(static_cast(floorf(1000.0f / fps)));
+}
+
+void Q3DWidget::hideEvent(QHideEvent* event)
+{
+ // React only to internal (pre/post-display)
+ // events
+ Q_UNUSED(event)
+ timer.stop();
}
osg::ref_ptr
@@ -263,6 +263,9 @@ Q3DWidget::getGlobalCursorPosition(int32_t cursorX, int32_t cursorY, double z)
void
Q3DWidget::redraw(void)
{
+#if (QGC_EVENTLOOP_DEBUG)
+ qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
+#endif
updateGL();
}
diff --git a/src/ui/map3D/Q3DWidget.h b/src/ui/map3D/Q3DWidget.h
index d82bad5604c0b40ac02d6d4add8b4bd038f77986..3ba2d6f233dd345240c0bd8b8035d0e67cca14fc 100644
--- a/src/ui/map3D/Q3DWidget.h
+++ b/src/ui/map3D/Q3DWidget.h
@@ -122,8 +122,10 @@ protected slots:
protected:
- /** @brief Enable / disable widget updating */
+ /** @brief Start widget updating */
void showEvent(QShowEvent* event);
+ /** @brief Stop widget updating */
+ void hideEvent(QHideEvent* event);
/**
* @brief Get base robot geode.
diff --git a/src/ui/map3D/QGCGoogleEarthView.cc b/src/ui/map3D/QGCGoogleEarthView.cc
index e1a2d591d0a7df1e69db295e7fdf64b3a72ede6d..0ae4284c2bd64c7b72a6dd1d3ca9870680115335 100644
--- a/src/ui/map3D/QGCGoogleEarthView.cc
+++ b/src/ui/map3D/QGCGoogleEarthView.cc
@@ -2,8 +2,8 @@
#include
#include
#include
-#include
-#include
+#include
+#include
#include
#include
@@ -16,6 +16,7 @@
#include "QGCWebPage.h"
#endif
+#include "QGC.h"
#include "ui_QGCGoogleEarthView.h"
#include "QGCGoogleEarthView.h"
@@ -102,7 +103,8 @@ QGCGoogleEarthView::~QGCGoogleEarthView()
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
#ifdef Q_OS_MAC
- webViewMac->page()->currentFrame()->evaluateJavaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg(uas->getColor().name()));
+ // uasid, type, color (in aarrbbgg format)
+ webViewMac->page()->currentFrame()->evaluateJavaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg(uas->getColor().name().remove(0, 1).prepend("50")));
#endif
#ifdef _MSC_VER
//if (webViewMac->page()->currentFrame()->evaluateJavaScript("isInitialized();").toBool())
@@ -134,6 +136,9 @@ void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, dou
Q_UNUSED(usec);
#ifdef Q_OS_MAC
webViewMac->page()->currentFrame()->evaluateJavaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
+
+ //qDebug() << QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15);
+
#endif
#ifdef _MSC_VER
//if (webViewMac->page()->currentFrame()->evaluateJavaScript("isInitialized();").toBool())
@@ -180,20 +185,17 @@ void QGCGoogleEarthView::setHome(double lat, double lon, double alt)
#endif
}
+void QGCGoogleEarthView::hideEvent(QHideEvent* event)
+{
+ Q_UNUSED(event) updateTimer->stop();
+}
+
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
- if (!event->spontaneous())
+ Q_UNUSED(event)
{
- if (event->type() == QEvent::Hide)
- {
- // Disable widget
- updateTimer->stop();
- qDebug() << "STOPPED GOOGLE EARTH UPDATES";
- }
- else if (event->type() == QEvent::Show)
- {
// Enable widget, initialize on first run
if (!webViewInitialized)
{
@@ -240,7 +242,6 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event)
QTimer::singleShot(1000, this, SLOT(initializeGoogleEarth()));
updateTimer->start(refreshRateMs);
}
- }
}
}
@@ -285,6 +286,9 @@ void QGCGoogleEarthView::initializeGoogleEarth()
void QGCGoogleEarthView::updateState()
{
+#if (QGC_EVENTLOOP_DEBUG)
+ qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
+#endif
if (gEarthInitialized)
{
int uasId = 0;
diff --git a/src/ui/map3D/QGCGoogleEarthView.h b/src/ui/map3D/QGCGoogleEarthView.h
index c70ed77566902aec4f581802eaa50824b7febbe8..71aeb4a039c9bd9873eb63c9b585651091c4da1d 100644
--- a/src/ui/map3D/QGCGoogleEarthView.h
+++ b/src/ui/map3D/QGCGoogleEarthView.h
@@ -106,8 +106,10 @@ protected:
QWebView* webViewMac;
#endif
- /** @brief Enable / disable widget updating */
+ /** @brief Start widget updating */
void showEvent(QShowEvent* event);
+ /** @brief Stop widget updating */
+ void hideEvent(QHideEvent* event);
private:
#ifdef _MSC_VER
diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc
index 15fb3e6e962c34b364857a0a3e8e28d17db15313..7a3700420b3b9d1c398b8a7cb85c1594b2b2539f 100644
--- a/src/ui/uas/UASView.cc
+++ b/src/ui/uas/UASView.cc
@@ -1,5 +1,4 @@
/*=====================================================================
-
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT
@@ -10,15 +9,15 @@ This file is part of the PIXHAWK project
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
-
+
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
-
+
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see .
-
+
======================================================================*/
/**
@@ -33,6 +32,7 @@ This file is part of the PIXHAWK project
#include
#include
+#include "QGC.h"
#include "MG.h"
#include "UASManager.h"
#include "UASView.h"
@@ -62,7 +62,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
m_ui(new Ui::UASView)
{
m_ui->setupUi(this);
-
+
// Setup communication
//connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(receiveValue(int,QString,double,quint64)));
connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
@@ -79,10 +79,10 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(&(uas->getWaypointManager()), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
connect(UASManager::instance(), SIGNAL(activeUASStatusChanged(UASInterface*,bool)), this, SLOT(updateActiveUAS(UASInterface*,bool)));
-
+
// Setup UAS selection
connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
-
+
// Setup user interaction
connect(m_ui->liftoffButton, SIGNAL(clicked()), uas, SLOT(launch()));
connect(m_ui->haltButton, SIGNAL(clicked()), uas, SLOT(halt()));
@@ -91,9 +91,9 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
-
+
// Set static values
-
+
// Name
if (uas->getUASName() == "")
{
@@ -103,13 +103,12 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
{
m_ui->nameLabel->setText(uas->getUASName());
}
-
+
setBackgroundColor();
-
+
// Heartbeat fade
refreshTimer = new QTimer(this);
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
- refreshTimer->start(updateInterval);
}
UASView::~UASView()
@@ -182,7 +181,7 @@ void UASView::enterEvent(QEvent* event)
}
}
qDebug() << __FILE__ << __LINE__ << "IN FOCUS";
-
+
if (event->type() == QEvent::MouseButtonDblClick)
{
qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
@@ -202,33 +201,26 @@ void UASView::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
- if (!event->spontaneous())
- {
- if (event->type() == QEvent::Hide)
- {
- refreshTimer->stop();
- }
- else if (event->type() == QEvent::Show)
- {
- refreshTimer->start(updateInterval);
- }
- }
+ Q_UNUSED(event);
+ refreshTimer->start(updateInterval);
+}
+
+void UASView::hideEvent(QHideEvent* event)
+{
+ // React only to internal (pre-display)
+ // events
+ Q_UNUSED(event);
+ refreshTimer->stop();
}
void UASView::receiveHeartbeat(UASInterface* uas)
{
- if (uas == this->uas)
- {
- refreshTimer->stop();
- QString colorstyle;
- heartbeatColor = QColor(20, 200, 20);
- colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",
- heartbeatColor.red(), heartbeatColor.green(), heartbeatColor.blue());
- m_ui->heartbeatIcon->setStyleSheet(colorstyle);
- m_ui->heartbeatIcon->setAutoFillBackground(true);
- refreshTimer->stop();
- refreshTimer->start(updateInterval);
- }
+ QString colorstyle;
+ heartbeatColor = QColor(20, 200, 20);
+ colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",
+ heartbeatColor.red(), heartbeatColor.green(), heartbeatColor.blue());
+ m_ui->heartbeatIcon->setStyleSheet(colorstyle);
+ m_ui->heartbeatIcon->setAutoFillBackground(true);
}
/**
@@ -280,8 +272,8 @@ void UASView::setSystemType(UASInterface* uas, unsigned int systemType)
m_ui->landButton->hide();
m_ui->shutdownButton->hide();
m_ui->abortButton->hide();
- m_ui->typeButton->setIcon(QIcon(":/images/mavs/groundstation.svg"));
- }
+ m_ui->typeButton->setIcon(QIcon(":/images/mavs/groundstation.svg"));
+ }
break;
default:
m_ui->typeButton->setIcon(QIcon(":/images/mavs/unknown.svg"));
@@ -395,90 +387,93 @@ void UASView::refresh()
if (generalUpdateCount == 4)
{
+#if (QGC_EVENTLOOP_DEBUG)
+ qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
+#endif
generalUpdateCount = 0;
//qDebug() << "UPDATING EVERYTHING";
- // State
- m_ui->stateLabel->setText(state);
- m_ui->statusTextLabel->setText(stateDesc);
-
- // Battery
- m_ui->batteryBar->setValue(static_cast(this->chargeLevel));
- //m_ui->loadBar->setValue(static_cast(this->load));
- m_ui->thrustBar->setValue(this->thrust);
-
- // Position
- QString position;
- position = position.sprintf("%02.2f %02.2f %02.2f m", x, y, z);
- m_ui->positionLabel->setText(position);
- QString globalPosition;
- QString latIndicator;
- if (lat > 0)
- {
- latIndicator = "N";
- }
- else
- {
- latIndicator = "S";
- }
- QString lonIndicator;
- if (lon > 0)
- {
- lonIndicator = "E";
- }
- else
- {
- lonIndicator = "W";
- }
- globalPosition = globalPosition.sprintf("%02.2f%s %02.2f%s %02.2f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
- m_ui->gpsLabel->setText(globalPosition);
+ // State
+ m_ui->stateLabel->setText(state);
+ m_ui->statusTextLabel->setText(stateDesc);
+
+ // Battery
+ m_ui->batteryBar->setValue(static_cast(this->chargeLevel));
+ //m_ui->loadBar->setValue(static_cast(this->load));
+ m_ui->thrustBar->setValue(this->thrust);
+
+ // Position
+ QString position;
+ position = position.sprintf("%02.2f %02.2f %02.2f m", x, y, z);
+ m_ui->positionLabel->setText(position);
+ QString globalPosition;
+ QString latIndicator;
+ if (lat > 0)
+ {
+ latIndicator = "N";
+ }
+ else
+ {
+ latIndicator = "S";
+ }
+ QString lonIndicator;
+ if (lon > 0)
+ {
+ lonIndicator = "E";
+ }
+ else
+ {
+ lonIndicator = "W";
+ }
+ globalPosition = globalPosition.sprintf("%02.2f%s %02.2f%s %02.2f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
+ m_ui->gpsLabel->setText(globalPosition);
- // Altitude
- if (groundDistance == 0 && alt != 0)
- {
- m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt));
- }
- else
- {
- m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance));
- }
+ // Altitude
+ if (groundDistance == 0 && alt != 0)
+ {
+ m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt));
+ }
+ else
+ {
+ m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance));
+ }
- // Speed
- QString speed;
- speed = speed.sprintf("%02.2f m/s", totalSpeed);
- m_ui->speedLabel->setText(speed);
+ // Speed
+ QString speed;
+ speed = speed.sprintf("%02.2f m/s", totalSpeed);
+ m_ui->speedLabel->setText(speed);
- // Thrust
- m_ui->thrustBar->setValue(thrust * 100);
+ // Thrust
+ m_ui->thrustBar->setValue(thrust * 100);
- if(this->timeRemaining > 1 && this->timeRemaining < MG::MAX_FLIGHT_TIME)
- {
- // Filter output to get a higher stability
- static double filterTime = static_cast(this->timeRemaining);
- filterTime = 0.8 * filterTime + 0.2 * static_cast(this->timeRemaining);
- int sec = static_cast(filterTime - static_cast(filterTime / 60.0f) * 60);
+ if(this->timeRemaining > 1 && this->timeRemaining < MG::MAX_FLIGHT_TIME)
+ {
+ // Filter output to get a higher stability
+ static double filterTime = static_cast(this->timeRemaining);
+ filterTime = 0.8 * filterTime + 0.2 * static_cast(this->timeRemaining);
+ int sec = static_cast(filterTime - static_cast(filterTime / 60.0f) * 60);
+ int min = static_cast(filterTime / 60);
+ int hours = static_cast(filterTime - min * 60 - sec);
+
+ QString timeText;
+ timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
+ m_ui->timeRemainingLabel->setText(timeText);
+ }
+ else
+ {
+ m_ui->timeRemainingLabel->setText(tr("Calculating"));
+ }
+
+ // Time Elapsed
+ //QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime());
+
+ quint64 filterTime = uas->getUptime() / 1000;
+ int sec = static_cast(filterTime - static_cast(filterTime / 60) * 60);
int min = static_cast(filterTime / 60);
int hours = static_cast(filterTime - min * 60 - sec);
-
QString timeText;
timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
- m_ui->timeRemainingLabel->setText(timeText);
+ m_ui->timeElapsedLabel->setText(timeText);
}
- else
- {
- m_ui->timeRemainingLabel->setText(tr("Calculating"));
- }
-
- // Time Elapsed
- //QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime());
-
- quint64 filterTime = uas->getUptime() / 1000;
- int sec = static_cast(filterTime - static_cast(filterTime / 60) * 60);
- int min = static_cast(filterTime / 60);
- int hours = static_cast(filterTime - min * 60 - sec);
- QString timeText;
- timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
- m_ui->timeElapsedLabel->setText(timeText);
-}
generalUpdateCount++;
// Fade heartbeat icon
diff --git a/src/ui/uas/UASView.h b/src/ui/uas/UASView.h
index 6775c5d3d01ba8b2d229882385cf8e61a9b0e97f..74dcc3c963feb5629514d19e682b4acaef5e910f 100644
--- a/src/ui/uas/UASView.h
+++ b/src/ui/uas/UASView.h
@@ -107,8 +107,10 @@ protected:
void enterEvent(QEvent* event);
/** @brief Mouse leaves the widget */
void leaveEvent(QEvent* event);
- /** @brief Enable / disable widget updating */
+ /** @brief Start widget updating */
void showEvent(QShowEvent* event);
+ /** @brief Stop widget updating */
+ void hideEvent(QHideEvent* event);
private:
Ui::UASView *m_ui;