Browse Source

Merge remote-tracking branch 'remotes/pixhawk/v10release' into dev_senseSoarMavlinkv10

QGC4.4
oberion 14 years ago
parent
commit
5505fab48e
  1. 6078
      files/vehicles/SenseSoar_Airplane/senseSoarDummy.dae
  2. 5681
      files/vehicles/sFly_Hexrotor/sfly-hex.dae
  3. BIN
      files/vehicles/sFly_Hexrotor/sfly-hex.skp
  4. 77
      images/earth.html
  5. 4
      qgroundcontrol.pri
  6. 4
      src/GAudioOutput.cc
  7. 4
      src/comm/MAVLinkSimulationMAV.cc
  8. 2
      src/comm/QGCFlightGearLink.cc
  9. 2
      src/comm/UDPLink.cc
  10. 2
      src/libs/opmapcontrol/src/core/providerstrings.cpp
  11. 1
      src/libs/opmapcontrol/src/mapwidget/waypointlineitem.cpp
  12. 15
      src/uas/PxQuadMAV.cc
  13. 24
      src/uas/UAS.cc
  14. 4
      src/ui/HDDisplay.cc
  15. 24
      src/ui/QGCMAVLinkInspector.cc
  16. 3
      src/ui/QGCMAVLinkInspector.h
  17. 4
      src/ui/linechart/LinechartWidget.cc
  18. 29
      src/ui/map3D/QGCGoogleEarthView.cc
  19. 163
      src/ui/uas/UASView.cc
  20. 3
      src/ui/uas/UASView.h

6078
files/vehicles/SenseSoar_Airplane/senseSoarDummy.dae

File diff suppressed because one or more lines are too long

5681
files/vehicles/sFly_Hexrotor/sfly-hex.dae

File diff suppressed because one or more lines are too long

BIN
files/vehicles/sFly_Hexrotor/sfly-hex.skp

Binary file not shown.

77
images/earth.html

@ -1,4 +1,4 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd"> <!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html> <html>
<head> <head>
@ -7,8 +7,8 @@
<!-- QGroundControl --> <!-- QGroundControl -->
<title>QGroundControl Google Earth View</title> <title>QGroundControl Google Earth View</title>
<!-- *** Replace the key below below with your own API key, available at http://code.google.com/apis/maps/signup.html *** --> <!-- *** Replace the key below below with your own API key, available at http://code.google.com/apis/maps/signup.html *** -->
<!--<script type="text/javascript" src="https://getfirebug.com/firebug-lite-beta.js"></script>--> <script type="text/javascript" src="https://getfirebug.com/firebug-lite-beta.js"></script>
<script type="text/javascript" src="http://www.google.com/jsapi?key=ABQIAAAAwbkbZLyhsmTCWXbTcjbgbRSzHs7K5SvaUdm8ua-Xxy_-2dYwMxQMhnagaawTo7L1FE1-amhuQxIlXw"></script> <script type="text/javascript" src="https://www.google.com/jsapi?key=ABQIAAAA5Q6wxQ6lxKS8haLVdUJaqhSjosg_0jiTTs2iXtkDVG0n0If1mBRHzhWw5VqBZX-j4NuzoVpU-UaHVg"></script>
<script type="text/javascript"> <script type="text/javascript">
google.load("earth", "1", { 'language': 'en'}); google.load("earth", "1", { 'language': 'en'});
@ -99,6 +99,12 @@ var clickMode = 0;
var homePlacemark = null; var homePlacemark = null;
// Data / heightmap
var heightMapPlacemark = null;
var heightMapModel = null;
function getGlobal(variable) function getGlobal(variable)
{ {
return variable; return variable;
@ -417,8 +423,16 @@ function createAircraft(id, type, color)
planeOrient = ge.createOrientation(''); planeOrient = ge.createOrientation('');
planeModel.setOrientation(planeOrient); planeModel.setOrientation(planeOrient);
planeLink.setHref('http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae'); var factor = 1.0;
//planeLink.setHref('http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae');
planeLink.setHref('http://qgroundcontrol.org/_media/users/models/sfly-hex.dae');
factor = 1.0/1000.0;
//planeLink.setHref('http://qgroundcontrol.org/_media/users/models/ascent-park-glider.dae');
planeModel.setLink(planeLink); planeModel.setLink(planeLink);
var scale = planeModel.getScale();
scale.set(scale.getX()*factor, scale.getY()*factor, scale.getZ()*factor)
planeModel.setScale(scale);
planeModel.setAltitudeMode (ge.ALTITUDE_ABSOLUTE); planeModel.setAltitudeMode (ge.ALTITUDE_ABSOLUTE);
planeLoc.setLatitude(currLat); planeLoc.setLatitude(currLat);
@ -553,6 +567,34 @@ function initCallback(object)
enableEventListener(); enableEventListener();
document.getElementById('JScript_initialized').setAttribute('value','true'); document.getElementById('JScript_initialized').setAttribute('value','true');
// Load heightmap
// http://www.inf.ethz.ch/personal/lomeier/data/untex-environment.dae
heightMapPlacemark = ge.createPlacemark('');
heightMapPlacemark.setName('aircraft');
heightMapModel = ge.createModel('');
ge.getFeatures().appendChild(heightMapPlacemark);
planeLoc = ge.createLocation('');
heightMapModel.setLocation(planeLoc);
planeLink = ge.createLink('');
planeOrient = ge.createOrientation('');
heightMapModel.setOrientation(planeOrient);
planeLink.setHref('http://www.inf.ethz.ch/personal/lomeier/data/untex-environment.dae');
heightMapModel.setLink(planeLink);
var scale = heightMapModel.getScale();
var factor = 1.0;//1.0/1000.0;
scale.set(scale.getX()*factor, scale.getY()*factor, scale.getZ()*factor)
heightMapModel.setScale(scale);
heightMapModel.setAltitudeMode (ge.ALTITUDE_ABSOLUTE);
planeLoc.setLatitude(currLat);
planeLoc.setLongitude(currLon);
planeLoc.setAltitude(currAlt);
heightMapPlacemark.setGeometry(heightMapModel);
initialized = true; initialized = true;
} }
@ -578,18 +620,16 @@ function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
currAlt = trueGroundAlt+0.1; currAlt = trueGroundAlt+0.1;
} }
// Interpolate between t-1 and t and set new states // Interpolate between t-1 and t and set new states
lastLat = lastLat*0.8+currLat*0.2; lastLat = lastLat*0.5+currLat*0.5;
lastLon = lastLon*0.8+currLon*0.2; lastLon = lastLon*0.5+currLon*0.5;
lastAlt = lastAlt*0.8+currAlt*0.2; lastAlt = lastAlt*0.5+currAlt*0.5;
//currFollowHeading = ((yaw/M_PI)+1.0)*360.0;
planeOrient.setRoll(+((roll/M_PI))*180.0);
planeOrient.setRoll(+((pitch / M_PI)) * 180.0); planeOrient.setTilt(-((pitch/M_PI))*180.0);
planeOrient.setTilt(-((roll / M_PI)) * 180.0); planeOrient.setHeading(((yaw/M_PI))*180.0-90.0);
planeOrient.setHeading(((yaw / M_PI)) * 180.0 - 90.0);
planeModel.setOrientation(planeOrient); planeModel.setOrientation(planeOrient);
currFollowHeading = ((yaw/M_PI))*180.0; currFollowHeading = currFollowHeading*0.95+0.05*(((yaw/M_PI))*180.0);
planeLoc.setLatitude(lastLat); planeLoc.setLatitude(lastLat);
planeLoc.setLongitude(lastLon); planeLoc.setLongitude(lastLon);
@ -678,17 +718,10 @@ function updateFollowAircraft()
if (viewMode != 3) // VIEW_MODE_CHASE_FREE if (viewMode != 3) // VIEW_MODE_CHASE_FREE
{ {
ge.getView().setAbstractView(currView); currView.setTilt(currFollowTilt);
var camera = ge.getView().copyAsCamera(ge.ALTITUDE_ABSOLUTE); currView.setHeading(currFollowHeading);
camera.setTilt(currFollowTilt);
camera.setRoll(0);
camera.setHeading(currFollowHeading);
ge.getView().setAbstractView(camera);
} }
else
{
ge.getView().setAbstractView(currView); ge.getView().setAbstractView(currView);
}
} }
function failureCallback(object) function failureCallback(object)

4
qgroundcontrol.pri

@ -42,8 +42,8 @@ macx {
# COMPILER_VERSION = $$system(gcc -v) # COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION) #message(Using compiler $$COMPILER_VERSION)
CONFIG += x86_64 cocoa phonon CONFIG += x86 cocoa phonon
CONFIG -= x86 CONFIG -= x86_64
#HARDWARE_PLATFORM = $$system(uname -a) #HARDWARE_PLATFORM = $$system(uname -a)
#contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) { #contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) {

4
src/GAudioOutput.cc

@ -184,8 +184,8 @@ bool GAudioOutput::say(QString text, int severity)
cst_wave* wav = flite_text_to_wave(text.toStdString().c_str(), v); cst_wave* wav = flite_text_to_wave(text.toStdString().c_str(), v);
// file.fileName() returns the unique file name // file.fileName() returns the unique file name
cst_wave_save(wav, file.fileName().toStdString().c_str(), "riff"); cst_wave_save(wav, file.fileName().toStdString().c_str(), "riff");
m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str()));
m_media->play(); //m_media->play();
res = true; res = true;
} }
#endif #endif

4
src/comm/MAVLinkSimulationMAV.cc

@ -14,10 +14,10 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
timer1Hz(0), timer1Hz(0),
latitude(lat), latitude(lat),
longitude(lon), longitude(lon),
altitude(0.0), altitude(550.0),
x(lat), x(lat),
y(lon), y(lon),
z(550), z(altitude),
roll(0.0), roll(0.0),
pitch(0.0), pitch(0.0),
yaw(0.0), yaw(0.0),

2
src/comm/QGCFlightGearLink.cc

@ -188,7 +188,7 @@ void QGCFlightGearLink::writeBytes(const char* data, qint64 size)
void QGCFlightGearLink::readBytes() void QGCFlightGearLink::readBytes()
{ {
const qint64 maxLength = 65536; const qint64 maxLength = 65536;
static char data[maxLength]; char data[maxLength];
QHostAddress sender; QHostAddress sender;
quint16 senderPort; quint16 senderPort;

2
src/comm/UDPLink.cc

@ -210,7 +210,7 @@ void UDPLink::writeBytes(const char* data, qint64 size)
void UDPLink::readBytes() void UDPLink::readBytes()
{ {
const qint64 maxLength = 65536; const qint64 maxLength = 65536;
static char data[maxLength]; char data[maxLength];
QHostAddress sender; QHostAddress sender;
quint16 senderPort; quint16 senderPort;

2
src/libs/opmapcontrol/src/core/providerstrings.cpp

@ -63,7 +63,7 @@ namespace core {
/// Google Maps API generated using http://greatmaps.codeplex.com/ /// Google Maps API generated using http://greatmaps.codeplex.com/
/// from http://code.google.com/intl/en-us/apis/maps/signup.html /// from http://code.google.com/intl/en-us/apis/maps/signup.html
/// </summary> /// </summary>
GoogleMapsAPIKey = "ABQIAAAAWaQgWiEBF3lW97ifKnAczhRAzBk5Igf8Z5n2W3hNnMT0j2TikxTLtVIGU7hCLLHMAuAMt-BO5UrEWA"; GoogleMapsAPIKey = "ABQIAAAA5Q6wxQ6lxKS8haLVdUJaqhSjosg_0jiTTs2iXtkDVG0n0If1mBRHzhWw5VqBZX-j4NuzoVpU-UaHVg";
// Yahoo version strings // Yahoo version strings
VersionYahooMap = "4.3"; VersionYahooMap = "4.3";

1
src/libs/opmapcontrol/src/mapwidget/waypointlineitem.cpp

@ -27,7 +27,6 @@ WaypointLineItem::WaypointLineItem(WayPointItem* wp1, WayPointItem* wp2, QColor
setLine(localPoint1.X(), localPoint1.Y(), localPoint2.X(), localPoint2.Y()); setLine(localPoint1.X(), localPoint1.Y(), localPoint2.X(), localPoint2.Y());
// Connect updates // Connect updates
// Update line from both waypoints // Update line from both waypoints
connect(wp1, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(updateWPValues(WayPointItem*))); connect(wp1, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(updateWPValues(WayPointItem*)));
connect(wp2, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(updateWPValues(WayPointItem*))); connect(wp2, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(updateWPValues(WayPointItem*)));

15
src/uas/PxQuadMAV.cc

@ -42,9 +42,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t* msg = &message; mavlink_message_t* msg = &message;
if (message.sysid == uasId) { if (message.sysid == uasId)
switch (message.msgid) { {
case MAVLINK_MSG_ID_RAW_AUX: { switch (message.msgid)
{
case MAVLINK_MSG_ID_RAW_AUX:
{
mavlink_raw_aux_t raw; mavlink_raw_aux_t raw;
mavlink_msg_raw_aux_decode(&message, &raw); mavlink_msg_raw_aux_decode(&message, &raw);
quint64 time = getUnixTime(0); quint64 time = getUnixTime(0);
@ -52,14 +55,16 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Temperature", "raw", raw.temp, time); emit valueChanged(uasId, "Temperature", "raw", raw.temp, time);
} }
break; break;
case MAVLINK_MSG_ID_IMAGE_TRIGGERED: { case MAVLINK_MSG_ID_IMAGE_TRIGGERED:
{
// FIXME Kind of a hack to load data from disk // FIXME Kind of a hack to load data from disk
mavlink_image_triggered_t img; mavlink_image_triggered_t img;
mavlink_msg_image_triggered_decode(&message, &img); mavlink_msg_image_triggered_decode(&message, &img);
emit imageStarted(img.timestamp); emit imageStarted(img.timestamp);
} }
break; break;
case MAVLINK_MSG_ID_PATTERN_DETECTED: { case MAVLINK_MSG_ID_PATTERN_DETECTED:
{
mavlink_pattern_detected_t detected; mavlink_pattern_detected_t detected;
mavlink_msg_pattern_detected_decode(&message, &detected); mavlink_msg_pattern_detected_decode(&message, &detected);
QByteArray b; QByteArray b;

24
src/uas/UAS.cc

@ -232,6 +232,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH); setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
break; break;
case MAV_TYPE_HEXAROTOR:
setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
break;
default: default:
// Do nothing // Do nothing
break; break;
@ -338,8 +341,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit loadChanged(this,state.load/10.0f); emit loadChanged(this,state.load/10.0f);
currentVoltage = state.voltage_battery/1000.0f; currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage); lpVoltage = filterVoltage(currentVoltage);
@ -463,7 +464,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit globalPositionChanged(this, latitude, longitude, altitude, time); emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time); emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state // Set internal state
if (!positionLock) { if (!positionLock)
{
// If position was not locked before, notify positive // If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive(); GAudioOutput::instance()->notifyPositive();
} }
@ -483,29 +485,35 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// quint64 time = getUnixTime(pos.time_usec); // quint64 time = getUnixTime(pos.time_usec);
quint64 time = getUnixTime(pos.time_usec); quint64 time = getUnixTime(pos.time_usec);
if (pos.fix_type > 2) { if (pos.fix_type > 2)
{
emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time); emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
latitude = pos.lat/(double)1E7; latitude = pos.lat/(double)1E7;
longitude = pos.lon/(double)1E7; longitude = pos.lon/(double)1E7;
altitude = pos.alt/1000.0; altitude = pos.alt/1000.0;
positionLock = true; positionLock = true;
isGlobalPositionKnown = true;
// Check for NaN // Check for NaN
int alt = pos.alt; int alt = pos.alt;
if (alt != alt) { if (!isnan(alt) && !isinf(alt))
{
alt = 0; alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE"); emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
} }
// FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time); // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
// Smaller than threshold and not NaN // Smaller than threshold and not NaN
float vel = pos.vel/100.0f; float vel = pos.vel/100.0f;
if (vel < 1000000 && !isnan(vel) && !isinf(vel)) { if (vel < 1000000 && !isnan(vel) && !isinf(vel))
{
// FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time); // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
//qDebug() << "GOT GPS RAW"; //qDebug() << "GOT GPS RAW";
// emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
} else { }
else
{
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel)); emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
} }
} }

4
src/ui/HDDisplay.cc

@ -186,9 +186,9 @@ void HDDisplay::triggerUpdate()
void HDDisplay::paintEvent(QPaintEvent * event) void HDDisplay::paintEvent(QPaintEvent * event)
{ {
Q_UNUSED(event); Q_UNUSED(event);
static quint64 interval = 0; quint64 interval = 0;
//qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__; //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
interval = MG::TIME::getGroundTimeNow(); interval = QGC::groundTimeMilliseconds();
renderOverlay(); renderOverlay();
} }

24
src/ui/QGCMAVLinkInspector.cc

@ -37,10 +37,10 @@ void QGCMAVLinkInspector::refreshView()
// Ignore NULL values // Ignore NULL values
if (!msg) continue; if (!msg) continue;
// Update the tree view // Update the tree view
QString messageName("%1 (%2 Hz, #%3)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(messagesHz.value(msg->msgid, 0), 2, 'f', 0).arg(msg->msgid);
if (!treeWidgetItems.contains(msg->msgid)) if (!treeWidgetItems.contains(msg->msgid))
{ {
QString messageName("%1 (#%2)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msg->msgid);
QStringList fields; QStringList fields;
fields << messageName; fields << messageName;
QTreeWidgetItem* widget = new QTreeWidgetItem(fields); QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
@ -56,7 +56,10 @@ void QGCMAVLinkInspector::refreshView()
ui->treeWidget->addTopLevelItem(widget); ui->treeWidget->addTopLevelItem(widget);
} }
// Set Hz
QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid); QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
message->setFirstColumnSpanned(true);
message->setData(0, Qt::DisplayRole, QVariant(messageName));
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i) for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{ {
updateField(msg->msgid, i, message->child(i)); updateField(msg->msgid, i, message->child(i));
@ -68,9 +71,22 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
{ {
Q_UNUSED(link); Q_UNUSED(link);
// Only overwrite if system filter is set // Only overwrite if system filter is set
// int filterValue = ui->systemComboBox()->value().toInt();
// if (filterValue != )
memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t)); memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
float msgHz = 0.0f;
quint64 receiveTime = QGC::groundTimeMilliseconds();
if (lastMessageUpdate.contains(message.msgid))
{
msgHz = 1000.0/(double)(receiveTime - lastMessageUpdate.value(message.msgid));
if (isinf(msgHz) || isnan(msgHz) || msgHz < 0.0f)
{
msgHz = 1;
}
float newHz = 0.001f*msgHz+0.999f*messagesHz.value(message.msgid, 1);
messagesHz.insert(message.msgid, newHz);
}
lastMessageUpdate.insert(message.msgid, receiveTime);
} }
QGCMAVLinkInspector::~QGCMAVLinkInspector() QGCMAVLinkInspector::~QGCMAVLinkInspector()

3
src/ui/QGCMAVLinkInspector.h

@ -26,7 +26,8 @@ public slots:
void refreshView(); void refreshView();
protected: protected:
QMap<int, quint64> lastFieldUpdate; ///< Used to switch between highlight and non-highlighting color QMap<int, quint64> lastMessageUpdate; ///< Used to switch between highlight and non-highlighting color
QMap<int, float> messagesHz; ///< Used to store update rate in Hz
mavlink_message_t receivedMessages[256]; ///< Available / known messages mavlink_message_t receivedMessages[256]; ///< Available / known messages
QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items
QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI

4
src/ui/linechart/LinechartWidget.cc

@ -315,6 +315,7 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
@ -347,6 +348,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
@ -391,6 +393,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
@ -425,6 +428,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;

29
src/ui/map3D/QGCGoogleEarthView.cc

@ -54,15 +54,15 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
#ifdef _MSC_VER #ifdef _MSC_VER
// Create layout and attach webViewWin // Create layout and attach webViewWin
QFile file("doc.html"); // QFile file("doc.html");
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) // if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
qDebug() << __FILE__ << __LINE__ << "Could not open log file"; // qDebug() << __FILE__ << __LINE__ << "Could not open log file";
QTextStream out(&file); // QTextStream out(&file);
out << webViewWin->generateDocumentation(); // out << webViewWin->generateDocumentation();
out.flush(); // out.flush();
file.flush(); // file.flush();
file.close(); // file.close();
#else #else
@ -284,8 +284,6 @@ void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, dou
{ {
Q_UNUSED(usec); Q_UNUSED(usec);
javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 22).arg(lon, 0, 'f', 22).arg(alt, 0, 'f', 22)); javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 22).arg(lon, 0, 'f', 22).arg(alt, 0, 'f', 22));
//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);
} }
void QGCGoogleEarthView::clearTrails() void QGCGoogleEarthView::clearTrails()
@ -614,7 +612,8 @@ void QGCGoogleEarthView::updateState()
#if (QGC_EVENTLOOP_DEBUG) #if (QGC_EVENTLOOP_DEBUG)
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__; qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif #endif
if (gEarthInitialized) { if (gEarthInitialized)
{
int uasId = 0; int uasId = 0;
double lat = 47.3769; double lat = 47.3769;
double lon = 8.549444; double lon = 8.549444;
@ -628,6 +627,8 @@ void QGCGoogleEarthView::updateState()
QList<UASInterface*> mavs = UASManager::instance()->getUASList(); QList<UASInterface*> mavs = UASManager::instance()->getUASList();
foreach (UASInterface* currMav, mavs) foreach (UASInterface* currMav, mavs)
{ {
// Only update if known
if (!currMav->globalPositionKnown()) continue;
uasId = currMav->getUASID(); uasId = currMav->getUASID();
lat = currMav->getLatitude(); lat = currMav->getLatitude();
lon = currMav->getLongitude(); lon = currMav->getLongitude();
@ -640,9 +641,9 @@ void QGCGoogleEarthView::updateState()
javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);") javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
.arg(uasId) .arg(uasId)
.arg(lat, 0, 'f', 15) .arg(lat, 0, 'f', 22)
.arg(lon, 0, 'f', 15) .arg(lon, 0, 'f', 22)
.arg(alt, 0, 'f', 15) .arg(alt, 0, 'f', 22)
.arg(roll, 0, 'f', 9) .arg(roll, 0, 'f', 9)
.arg(pitch, 0, 'f', 9) .arg(pitch, 0, 'f', 9)
.arg(yaw, 0, 'f', 9)); .arg(yaw, 0, 'f', 9));

163
src/ui/uas/UASView.cc

@ -35,7 +35,6 @@ This file is part of the PIXHAWK project
#include <QInputDialog> #include <QInputDialog>
#include "QGC.h" #include "QGC.h"
#include "MG.h"
#include "UASManager.h" #include "UASManager.h"
#include "UASView.h" #include "UASView.h"
#include "UASWaypointManager.h" #include "UASWaypointManager.h"
@ -65,6 +64,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
alt(0), alt(0),
groundDistance(0), groundDistance(0),
localFrame(false), localFrame(false),
globalFrameKnown(false),
removeAction(new QAction("Delete this system", this)), removeAction(new QAction("Delete this system", this)),
renameAction(new QAction("Rename..", this)), renameAction(new QAction("Rename..", this)),
selectAction(new QAction("Control this system", this )), selectAction(new QAction("Control this system", this )),
@ -72,6 +72,8 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
selectAirframeAction(new QAction("Choose Airframe", this)), selectAirframeAction(new QAction("Choose Airframe", this)),
setBatterySpecsAction(new QAction("Set Battery Options", this)), setBatterySpecsAction(new QAction("Set Battery Options", this)),
lowPowerModeEnabled(true), lowPowerModeEnabled(true),
generalUpdateCount(0),
filterTime(0),
m_ui(new Ui::UASView) m_ui(new Ui::UASView)
{ {
// FIXME XXX // FIXME XXX
@ -127,9 +129,12 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
// Set static values // Set static values
// Name // Name
if (uas->getUASName() == "") { if (uas->getUASName() == "")
{
m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID())); m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID()));
} else { }
else
{
m_ui->nameLabel->setText(uas->getUASName()); m_ui->nameLabel->setText(uas->getUASName());
} }
@ -141,7 +146,9 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
if (lowPowerModeEnabled) if (lowPowerModeEnabled)
{ {
refreshTimer->start(updateInterval*3); refreshTimer->start(updateInterval*3);
} else { }
else
{
refreshTimer->start(updateInterval); refreshTimer->start(updateInterval);
} }
@ -194,10 +201,13 @@ void UASView::setBackgroundColor()
QColor uasColor = uas->getColor(); QColor uasColor = uas->getColor();
QString colorstyle; QString colorstyle;
QString borderColor = "#4A4A4F"; QString borderColor = "#4A4A4F";
if (isActive) { if (isActive)
{
borderColor = "#FA4A4F"; borderColor = "#FA4A4F";
uasColor = uasColor.darker(475); uasColor = uasColor.darker(475);
} else { }
else
{
uasColor = uasColor.darker(675); uasColor = uasColor.darker(675);
} }
colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }", colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }",
@ -207,14 +217,16 @@ void UASView::setBackgroundColor()
void UASView::setUASasActive(bool active) void UASView::setUASasActive(bool active)
{ {
if (active) { if (active)
{
UASManager::instance()->setActiveUAS(this->uas); UASManager::instance()->setActiveUAS(this->uas);
} }
} }
void UASView::updateActiveUAS(UASInterface* uas, bool active) void UASView::updateActiveUAS(UASInterface* uas, bool active)
{ {
if (uas == this->uas) { if (uas == this->uas)
{
this->isActive = active; this->isActive = active;
setBackgroundColor(); setBackgroundColor();
} }
@ -239,22 +251,25 @@ void UASView::mouseDoubleClickEvent (QMouseEvent * event)
void UASView::enterEvent(QEvent* event) void UASView::enterEvent(QEvent* event)
{ {
if (event->type() == QEvent::MouseMove) { if (event->type() == QEvent::MouseMove)
{
emit uasInFocus(uas); emit uasInFocus(uas);
if (uas != UASManager::instance()->getActiveUAS()) { if (uas != UASManager::instance()->getActiveUAS())
{
grabMouse(QCursor(Qt::PointingHandCursor)); grabMouse(QCursor(Qt::PointingHandCursor));
} }
} }
// qDebug() << __FILE__ << __LINE__ << "IN FOCUS";
if (event->type() == QEvent::MouseButtonDblClick) { if (event->type() == QEvent::MouseButtonDblClick)
{
// qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!"; // qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
} }
} }
void UASView::leaveEvent(QEvent* event) void UASView::leaveEvent(QEvent* event)
{ {
if (event->type() == QEvent::MouseMove) { if (event->type() == QEvent::MouseMove)
{
emit uasOutFocus(uas); emit uasOutFocus(uas);
releaseMouse(); releaseMouse();
} }
@ -300,9 +315,11 @@ void UASView::updateName(const QString& name)
*/ */
void UASView::setSystemType(UASInterface* uas, unsigned int systemType) void UASView::setSystemType(UASInterface* uas, unsigned int systemType)
{ {
if (uas == this->uas) { if (uas == this->uas)
{
// Set matching icon // Set matching icon
switch (systemType) { switch (systemType)
{
case 0: case 0:
m_ui->typeButton->setIcon(QIcon(":/images/mavs/generic.svg")); m_ui->typeButton->setIcon(QIcon(":/images/mavs/generic.svg"));
break; break;
@ -354,9 +371,7 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double
this->x = x; this->x = x;
this->y = y; this->y = y;
this->z = z; this->z = z;
if (!localFrame) {
localFrame = true; localFrame = true;
}
} }
void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec) void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
@ -366,6 +381,7 @@ void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, do
this->lon = lon; this->lon = lon;
this->lat = lat; this->lat = lat;
this->alt = alt; this->alt = alt;
globalFrameKnown = true;
} }
void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec) void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec)
@ -386,8 +402,10 @@ void UASView::setWaypoint(int uasId, int id, double x, double y, double z, doubl
Q_UNUSED(z); Q_UNUSED(z);
Q_UNUSED(yaw); Q_UNUSED(yaw);
Q_UNUSED(autocontinue); Q_UNUSED(autocontinue);
if (uasId == this->uas->getUASID()) { if (uasId == this->uas->getUASID())
if (current) { {
if (current)
{
m_ui->waypointLabel->setText(tr("WP") + QString::number(id)); m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
} }
} }
@ -395,14 +413,16 @@ void UASView::setWaypoint(int uasId, int id, double x, double y, double z, doubl
void UASView::selectWaypoint(int uasId, int id) void UASView::selectWaypoint(int uasId, int id)
{ {
if (uasId == this->uas->getUASID()) { if (uasId == this->uas->getUASID())
{
m_ui->waypointLabel->setText(tr("WP") + QString::number(id)); m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
} }
} }
void UASView::updateThrust(UASInterface* uas, double thrust) void UASView::updateThrust(UASInterface* uas, double thrust)
{ {
if (this->uas == uas) { if (this->uas == uas)
{
this->thrust = thrust; this->thrust = thrust;
} }
} }
@ -410,7 +430,8 @@ void UASView::updateThrust(UASInterface* uas, double thrust)
void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{ {
Q_UNUSED(voltage); Q_UNUSED(voltage);
if (this->uas == uas) { if (this->uas == uas)
{
timeRemaining = seconds; timeRemaining = seconds;
chargeLevel = percent; chargeLevel = percent;
} }
@ -418,7 +439,8 @@ void UASView::updateBattery(UASInterface* uas, double voltage, double percent, i
void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription) void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription)
{ {
if (this->uas == uas) { if (this->uas == uas)
{
state = uasState; state = uasState;
stateDesc = stateDescription; stateDesc = stateDescription;
} }
@ -426,7 +448,8 @@ void UASView::updateState(UASInterface* uas, QString uasState, QString stateDesc
void UASView::updateLoad(UASInterface* uas, double load) void UASView::updateLoad(UASInterface* uas, double load)
{ {
if (this->uas == uas) { if (this->uas == uas)
{
this->load = load; this->load = load;
} }
} }
@ -437,7 +460,8 @@ void UASView::contextMenuEvent (QContextMenuEvent* event)
menu.addAction(selectAction); menu.addAction(selectAction);
menu.addSeparator(); menu.addSeparator();
menu.addAction(renameAction); menu.addAction(renameAction);
if (timeout) { if (timeout)
{
menu.addAction(removeAction); menu.addAction(removeAction);
} }
menu.addAction(hilAction); menu.addAction(hilAction);
@ -448,7 +472,8 @@ void UASView::contextMenuEvent (QContextMenuEvent* event)
void UASView::setBatterySpecs() void UASView::setBatterySpecs()
{ {
if (uas) { if (uas)
{
bool ok; bool ok;
QString newName = QInputDialog::getText(this, tr("Set Battery Specifications for %1").arg(uas->getUASName()), QString newName = QInputDialog::getText(this, tr("Set Battery Specifications for %1").arg(uas->getUASName()),
tr("Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V) or just warn level in percent (e.g. 15%) to use estimate from MAV"), QLineEdit::Normal, tr("Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V) or just warn level in percent (e.g. 15%) to use estimate from MAV"), QLineEdit::Normal,
@ -460,7 +485,8 @@ void UASView::setBatterySpecs()
void UASView::rename() void UASView::rename()
{ {
if (uas) { if (uas)
{
bool ok; bool ok;
QString newName = QInputDialog::getText(this, tr("Rename System %1").arg(uas->getUASName()), QString newName = QInputDialog::getText(this, tr("Rename System %1").arg(uas->getUASName()),
tr("System Name:"), QLineEdit::Normal, tr("System Name:"), QLineEdit::Normal,
@ -472,7 +498,8 @@ void UASView::rename()
void UASView::selectAirframe() void UASView::selectAirframe()
{ {
if (uas) { if (uas)
{
// Get list of airframes from UAS // Get list of airframes from UAS
QStringList airframes; QStringList airframes;
airframes << "Generic" airframes << "Generic"
@ -484,12 +511,14 @@ void UASView::selectAirframe()
<< "Reaper" << "Reaper"
<< "Predator" << "Predator"
<< "Coaxial" << "Coaxial"
<< "Pteryx"; << "Pteryx"
<< "Asctec Firefly";
bool ok; bool ok;
QString item = QInputDialog::getItem(this, tr("Select Airframe for %1").arg(uas->getUASName()), QString item = QInputDialog::getItem(this, tr("Select Airframe for %1").arg(uas->getUASName()),
tr("Airframe"), airframes, uas->getAirframe(), false, &ok); tr("Airframe"), airframes, uas->getAirframe(), false, &ok);
if (ok && !item.isEmpty()) { if (ok && !item.isEmpty())
{
// Set this airframe as UAS airframe // Set this airframe as UAS airframe
uas->setAirframe(airframes.indexOf(item)); uas->setAirframe(airframes.indexOf(item));
} }
@ -501,15 +530,15 @@ void UASView::refresh()
//setUpdatesEnabled(false); //setUpdatesEnabled(false);
//setUpdatesEnabled(true); //setUpdatesEnabled(true);
//repaint(); //repaint();
//qDebug() << "UPDATING UAS WIDGET!" << uas->getUASName();
static quint64 lastupdate = 0;
//// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate = MG::TIME::getGroundTimeNow();
// FIXME quint64 lastupdate = 0;
static int generalUpdateCount = 0; //// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate = QGC::groundTimeMilliseconds();
if (generalUpdateCount == 4) { if (generalUpdateCount == 4)
{
#if (QGC_EVENTLOOP_DEBUG) #if (QGC_EVENTLOOP_DEBUG)
// qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__; // qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif #endif
@ -525,29 +554,48 @@ void UASView::refresh()
m_ui->thrustBar->setValue(this->thrust); m_ui->thrustBar->setValue(this->thrust);
// Position // Position
// If global position is known, prefer it over local coordinates
if (!globalFrameKnown && localFrame)
{
QString position; QString position;
position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z); position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z);
m_ui->positionLabel->setText(position); m_ui->positionLabel->setText(position);
}
if (globalFrameKnown)
{
QString globalPosition; QString globalPosition;
QString latIndicator; QString latIndicator;
if (lat > 0) { if (lat > 0)
{
latIndicator = "N"; latIndicator = "N";
} else { }
else
{
latIndicator = "S"; latIndicator = "S";
} }
QString lonIndicator; QString lonIndicator;
if (lon > 0) { if (lon > 0)
{
lonIndicator = "E"; lonIndicator = "E";
} else { }
else
{
lonIndicator = "W"; lonIndicator = "W";
} }
globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %06.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt); globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %06.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
m_ui->positionLabel->setText(globalPosition); m_ui->positionLabel->setText(globalPosition);
}
// Altitude // Altitude
if (groundDistance == 0 && alt != 0) { if (groundDistance == 0 && alt != 0)
{
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0')); m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0'));
} else { }
else
{
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0')); m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0'));
} }
@ -558,9 +606,10 @@ void UASView::refresh()
// Thrust // Thrust
m_ui->thrustBar->setValue(thrust * 100); m_ui->thrustBar->setValue(thrust * 100);
if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME) { if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME)
{
// Filter output to get a higher stability // Filter output to get a higher stability
static double filterTime = static_cast<int>(this->timeRemaining); filterTime = static_cast<int>(this->timeRemaining);
filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining); filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining);
int sec = static_cast<int>(filterTime - static_cast<int>(filterTime / 60.0f) * 60); int sec = static_cast<int>(filterTime - static_cast<int>(filterTime / 60.0f) * 60);
int min = static_cast<int>(filterTime / 60); int min = static_cast<int>(filterTime / 60);
@ -569,7 +618,9 @@ void UASView::refresh()
QString timeText; QString timeText;
timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
m_ui->timeRemainingLabel->setText(timeText); m_ui->timeRemainingLabel->setText(timeText);
} else { }
else
{
m_ui->timeRemainingLabel->setText(tr("Calc..")); m_ui->timeRemainingLabel->setText(tr("Calc.."));
} }
@ -588,29 +639,37 @@ void UASView::refresh()
QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }"); QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }");
if (timeout) { if (timeout)
{
// CRITICAL CONDITION, NO HEARTBEAT // CRITICAL CONDITION, NO HEARTBEAT
QString borderColor = "#FFFF00"; QString borderColor = "#FFFF00";
if (isActive) { if (isActive)
{
borderColor = "#FA4A4F"; borderColor = "#FA4A4F";
} }
if (iconIsRed) { if (iconIsRed)
{
QColor warnColor(Qt::red); QColor warnColor(Qt::red);
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name())); m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name()); QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
m_ui->uasViewFrame->setStyleSheet(style); m_ui->uasViewFrame->setStyleSheet(style);
} else { }
else
{
QColor warnColor(Qt::black); QColor warnColor(Qt::black);
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name())); m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name()); QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
m_ui->uasViewFrame->setStyleSheet(style); m_ui->uasViewFrame->setStyleSheet(style);
refreshTimer->setInterval(errorUpdateInterval); refreshTimer->setInterval(errorUpdateInterval);
refreshTimer->start();
} }
iconIsRed = !iconIsRed; iconIsRed = !iconIsRed;
} else { }
else
{
if (!lowPowerModeEnabled) if (!lowPowerModeEnabled)
{ {
// Fade heartbeat icon // Fade heartbeat icon
@ -620,6 +679,7 @@ void UASView::refresh()
//m_ui->heartbeatIcon->setAutoFillBackground(true); //m_ui->heartbeatIcon->setAutoFillBackground(true);
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name())); m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
refreshTimer->setInterval(updateInterval); refreshTimer->setInterval(updateInterval);
refreshTimer->start();
} }
} }
//setUpdatesEnabled(true); //setUpdatesEnabled(true);
@ -630,7 +690,8 @@ void UASView::refresh()
void UASView::changeEvent(QEvent *e) void UASView::changeEvent(QEvent *e)
{ {
QWidget::changeEvent(e); QWidget::changeEvent(e);
switch (e->type()) { switch (e->type())
{
case QEvent::LanguageChange: case QEvent::LanguageChange:
m_ui->retranslateUi(this); m_ui->retranslateUi(this);
break; break;

3
src/ui/uas/UASView.h

@ -117,6 +117,7 @@ protected:
float alt; float alt;
float groundDistance; float groundDistance;
bool localFrame; bool localFrame;
bool globalFrameKnown;
QAction* removeAction; QAction* removeAction;
QAction* renameAction; QAction* renameAction;
QAction* selectAction; QAction* selectAction;
@ -126,6 +127,8 @@ protected:
static const int updateInterval = 800; static const int updateInterval = 800;
static const int errorUpdateInterval = 200; static const int errorUpdateInterval = 200;
bool lowPowerModeEnabled; ///< Low power mode reduces update rates bool lowPowerModeEnabled; ///< Low power mode reduces update rates
unsigned int generalUpdateCount; ///< Skip counter for updates
double filterTime; ///< Filter time estimate of battery
void mouseDoubleClickEvent (QMouseEvent * event); void mouseDoubleClickEvent (QMouseEvent * event);

Loading…
Cancel
Save