Commit b7e9fe69 authored by pixhawk's avatar pixhawk

Substantially bugfixed and improved deactivation/activation and persistence of...

Substantially bugfixed and improved deactivation/activation and persistence of widgets. A lot of testing of Google Earth view, only minor improvements
parent 43ce5cca
......@@ -43,6 +43,9 @@ var aircraft = [];
var attitudes = [];
var locations = [];
var trails = [];
var trail;
var lineStringPlacemark;
var lineStyle;
// Aircraft class
......@@ -99,15 +102,14 @@ function setGCSHome(lat, lon, alt)
function createAircraft(id, type, color)
{
console.debug("Aircraft created");
var planePlacemark = ge.createPlacemark('');
planePlacemark = ge.createPlacemark('');
planePlacemark.setName('aircraft');
var planeModel = ge.createModel('');
planeModel = ge.createModel('');
ge.getFeatures().appendChild(planePlacemark);
var planeLoc = ge.createLocation('');
planeLoc = ge.createLocation('');
planeModel.setLocation(planeLoc);
var planeLink = ge.createLink('');
var planeOrient = ge.createOrientation('');
planeLink = ge.createLink('');
planeOrient = ge.createOrientation('');
planeModel.setOrientation(planeOrient);
planeLink.setHref('http://qgroundcontrol.org/_media/users/models/multiplex-twinstar.dae');
......@@ -125,40 +127,53 @@ console.debug("Aircraft created");
attitudes[id] = planeOrient;
locations[id] = planeLoc;
createTrail(id, color);
console.debug("Aircraft created");
//createTrail(id, color);
}
function createTrail(id, color)
{
// Create the placemark
var lineStringPlacemark = ge.createPlacemark('');
lineStringPlacemark = ge.createPlacemark('');
// Create the placemark
// Create the LineString; set it to extend down to the ground
// and set the altitude mode
trails[id] = ge.createLineString('');
lineStringPlacemark.setGeometry(trails[id]);
trails[id].setExtrude(true);
lineString.setAltitudeMode(ge.ALTITUDE_ABSOLUTE);
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(''));
var lineStyle = lineStringPlacemark.getStyleSelector().getLineStyle();
lineStyle = lineStringPlacemark.getStyleSelector().getLineStyle();
lineStyle.setWidth(5);
lineStyle.getColor().set('99bbaaff');
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)
{
//trails[id].getCoordinates().pushLatLngAlt(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)
......@@ -174,36 +189,10 @@ function initCallback(object)
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.setName('aircraft');
planeModel = ge.createModel('');
ge.getFeatures().appendChild(planePlacemark);
planeLoc = ge.createLocation('');
planeModel.setLocation(planeLoc);
planeLink = ge.createLink('');
planeOrient = ge.createOrientation('');
planeModel.setOrientation(planeOrient);
planeLink.setHref('http://qgroundcontrol.org/_media/users/models/multiplex-twinstar.dae');
planeModel.setLink(planeLink);
planeModel.setAltitudeMode (ge.ALTITUDE_ABSOLUTE);
planeLoc.setLatitude(currLat);
planeLoc.setLongitude(currLon);
planeLoc.setAltitude(currAlt);
createTrail(220, 'bb2222ff');
createAircraft(220);
planePlacemark.setGeometry(planeModel);
//setAircraftPositionAttitude(220, 47.3772, currLon, currAlt+50, 20, 15, 50);
//enableFollowing(true);
updateFollowAircraft();
initialized = true;
......@@ -232,6 +221,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);
......
......@@ -19,4 +19,6 @@ namespace QGC
const QString COMPANYNAME = "OPENMAV";
}
#define QGC_EVENTLOOP_DEBUG 0
#endif // QGC_H
......@@ -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,17 @@ void MAVLinkSimulationLink::mainloop()
// Move X Position
x = x*0.93f + 0.07f*(x+sin(static_cast<float>(QGC::groundTimeUsecs()) * 0.08f));
y = y*0.93f + 0.07f*(y+sin(static_cast<float>(QGC::groundTimeUsecs()) * 0.5f));
z = z*0.93f + 0.07f*(z+sin(static_cast<float>(QGC::groundTimeUsecs()*0.001f)) * 0.1f);
x = 8.0*sin(circleCounter);
y = 3.0*cos(circleCounter);
z = 1.8 + 1.2*sin(circleCounter/2.0);
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;
// 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;
......@@ -409,7 +410,7 @@ void MAVLinkSimulationLink::mainloop()
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.01), 8.54899892510421+(y*0.01), 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 +509,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 +522,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 +580,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 +592,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 +776,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";
}
}
......
......@@ -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;
......
......@@ -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
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
......@@ -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 <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......@@ -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;
}
}
......@@ -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 = "<<mlSinglePid.idx;
case MAVLINK_MSG_ID_PID: //182
memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
mavlink_msg_pid_decode(&message, &mlSinglePid);
qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;
emit slugsPidValues(uasId, mlSinglePid);
emit slugsPidValues(uasId, mlSinglePid);
break;
break;
case MAVLINK_MSG_ID_SLUGS_ACTION: //183
case MAVLINK_MSG_ID_SLUGS_ACTION: //183
break;
break;
#endif
default:
// qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
default:
// qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
break;
}
}
}
......
......@@ -211,7 +211,7 @@ public slots:
void addLink(LinkInterface* link);
/** @brief Receive a message from one of the communication links. */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
/** @brief Send a message over this link (to this or to all UAS on this link) */
void sendMessage(LinkInterface* link, mavlink_message_t message);
......
......@@ -38,6 +38,7 @@ This file is part of the PIXHAWK project
#include "HDDisplay.h"
#include "ui_HDDisplay.h"
#include "MG.h"
#include "QGC.h"
#ifndef M_PI
#define M_PI 3.14159265358979323846
#endif
......@@ -171,6 +172,9 @@ void HDDisplay::paintEvent(QPaintEvent * event)
void HDDisplay::renderOverlay()
{
#if (QGC_EVENTLOOP_DEBUG)
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
quint64 refreshInterval = 100;
quint64 currTime = MG::TIME::getGroundTimeNow();
if (currTime - lastPaintTime < refreshInterval)
......@@ -230,17 +234,17 @@ void HDDisplay::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)));
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)
// {
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 +667,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();
}
}
......
......@@ -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);
......
This diff is collapsed.
......@@ -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 */
......
......@@ -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;
......
......@@ -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;
......
This diff is collapsed.
......@@ -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)
......
......@@ -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:
......
......@@ -43,6 +43,8 @@ This file is part of the PIXHAWK project
#include <MG.h>
#include <QPaintEngine>
#include "QGC.h"
/**
* @brief The default constructor
*
......@@ -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;
......@@ -580,6 +594,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)
......
......@@ -301,6 +301,8 @@ protected:
// Methods
void addCurve(QString id);
QColor getNextColor();
void showEvent(QShowEvent* event);
void hideEvent(QHideEvent* event);
private:
TimeSeriesData* d_data;
......
......@@ -447,7 +447,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)
......
......@@ -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);
......
......@@ -10,28 +10,47 @@ Linecharts::Linecharts(QWidget *parent) :
plots(),
active(true)
{
this->setVisible(false);
// Get current MAV list
QList<UASInterface*> systems = UASManager::instance()->getUASList();
this->setVisible(false);
// Get current MAV list
QList<UASInterface*> 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<LinechartWidget*>(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<LinechartWidget*>(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);
}
}
}
......
......@@ -26,8 +26,10 @@ public slots:
protected:
QMap<int, LinechartWidget*> plots;
bool active;
/** @brief Start updating widget */
void showEvent(QShowEvent* event);
/** @brief Stop updating widget */
void hideEvent(QHideEvent* event);
};
......
......@@ -30,6 +30,7 @@ This file is part of the QGROUNDCONTROL project
*/
#include "Q3DWidget.h"
#include "QGC.h"
#include <osg/Geometry>
#include <osg/LineWidth>
......@@ -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<int>(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<int>(floorf(1000.0f / fps)));
}
}
Q_UNUSED(event)
timer.start(static_cast<int>(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<osg::Geode>
......@@ -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();
}
......
......@@ -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.
......
......@@ -12,6 +12,7 @@
#include "QGCWebPage.h"
#endif
#include "QGC.h"
#include "ui_QGCGoogleEarthView.h"
#include "QGCGoogleEarthView.h"
......@@ -85,7 +86,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())
......@@ -117,6 +119,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())
......@@ -163,20 +168,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)
{
......@@ -198,7 +200,6 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event)
QTimer::singleShot(1000, this, SLOT(initializeGoogleEarth()));
updateTimer->start(refreshRateMs);
}
}
}
}
......@@ -243,6 +244,9 @@ void QGCGoogleEarthView::initializeGoogleEarth()
void QGCGoogleEarthView::updateState()
{
#if (QGC_EVENTLOOP_DEBUG)
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
if (gEarthInitialized)
{
int uasId = 0;
......
......@@ -89,8 +89,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
......
This diff is collapsed.
......@@ -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;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment