Commit 125f823d authored by pixhawk's avatar pixhawk

Merge branch 'master' of pixhawk.ethz.ch:qgroundcontrol

parents 26ae477a b6a40520
*Makefile*
tags
build
Info.plist
obj
*.log
*~
*qtc*
bin/*.exe
bin/*.txt
bin/mac
*pro.user*
qrc_*.cpp
*.Debug
*.Release
tmp
debug
release
qgroundcontrol
mavlinkgen
*.wav
qgroundcontrol.xcodeproj/**
doc/html
doc/doxy.log
deploy/mac
deploy/linux
controller_log*
user_config.pri
*.app
*Makefile*
tags
build
Info.plist
obj
*.log
*~
*qtc*
bin/*.exe
bin/*.txt
bin/mac
*pro.user*
qrc_*.cpp
*.Debug
*.Release
tmp
debug
release
qgroundcontrol
mavlinkgen
*.wav
qgroundcontrol.xcodeproj/**
doc/html
doc/doxy.log
deploy/mac
deploy/linux
deploy/qgroundcontrol*
controller_log*
user_config.pri
*.app
*.ncb
*.vcproj
......@@ -39,4 +40,4 @@ user_config.pri
*.project
*.cproject
*.sln
*.suo
\ No newline at end of file
*.suo
#!/bin/sh
# Clean build directories
rm -rf mac
mkdir -p mac
# Change to build directory and compile application
cd ..
make -j4
# Copy and build the application bundle
cd deploy
cp -r ../bin/mac/qgroundcontrol.app mac/.
cp -r ../../qgroundcontrol-build-desktop/qgroundcontrol.app .
cp -r ../audio mac/qgroundcontrol.app/Contents/MacOs/.
mkdir -p mac/qgroundcontrol.app/Contents/Frameworks/
cp -r ../audio qgroundcontrol.app/Contents/MacOs/.
mkdir -p qgroundcontrol.app/Contents/Frameworks/
# SDL is not copied by Qt - for whatever reason
cp -r SDL.framework mac/qgroundcontrol.app/Contents/Frameworks/.
cp -r /Library/Frameworks/SDL.framework qgroundcontrol.app/Contents/Frameworks/.
echo -e '\n\nStarting to create disk image. This may take a while..\n'
macdeployqt mac/qgroundcontrol.app -dmg
rm -rf mac/qgroundcontrol.app
macdeployqt qgroundcontrol.app -dmg
rm -rf qgroundcontrol.app
echo -e '\n\n QGroundControl .DMG file is now ready for publishing\n'
......@@ -356,3 +356,38 @@ QProgressBar::chunk#speedBar {
QProgressBar::chunk#thrustBar {
background-color: orange;
}
QDialog {
border: 1px solid #62676B;
border-radius: 2px;
}
QTabWidget::pane { /* The tab widget frame */
border: 1px solid #62676B;
border-radius: 2px;
position: absolute;
top: -0.5em;
}
QTabWidget::tab-bar {
alignment: center;
}
/* Style the tab using the tab sub-control. Note that
it reads QTabBar _not_ QTabWidget */
QTabBar::tab {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535);
border: 2px solid #62676B;
border-radius: 4px;
min-width: 8ex;
padding: 2px;
}
QTabBar::tab:selected, QTabBar::tab:hover {
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535);
border: 2px solid #379AC3;
}
QTabBar::tab:selected {
border: 2px solid #379AC3;
}
......@@ -63,10 +63,10 @@ namespace qmapcontrol
void MapNetwork::requestFinished(int id, bool error)
{
// sleep(1);
// qDebug() << "MapNetwork::requestFinished" << http->state() << ", id: " << id;
qDebug() << "QMapControl: MapNetwork::requestFinished" << http->state() << ", id: " << id;
if (error)
{
qDebug() << "network error: " << http->errorString();
qDebug() << "QMapControl: network error: " << http->errorString();
//restart query
}
......@@ -79,7 +79,7 @@ namespace qmapcontrol
QString url = loadingMap[id];
loadingMap.remove(id);
vectorMutex.unlock();
// qDebug() << "request finished for id: " << id << ", belongs to: " << notifier.url << endl;
//qDebug() << "QMapControl: request finished for id: " << id << ", belongs to: " << notifier.url << endl;
QByteArray ax;
if (http->bytesAvailable()>0)
......@@ -87,17 +87,20 @@ namespace qmapcontrol
QPixmap pm;
ax = http->readAll();
qDebug() << "QMapControl: Request consisted of " << ax.size() << "bytes";
if (pm.loadFromData(ax))
{
loaded += pm.size().width()*pm.size().height()*pm.depth()/8/1024;
// qDebug() << "Network loaded: " << (loaded);
qDebug() << "QMapControl: Network loaded: " << (loaded);
parent->receivedImage(pm, url);
}
else if (pm.width() == 0 || pm.height() == 0)
{
// Silently ignore map request for a
// 0xn pixel map
qDebug() << "QMapControl: IGNORED 0x0 pixel map request, widthxheight:" << pm.width() << "x" << pm.height();
qDebug() << "QMapControl: HTML ERROR MESSAGE:" << ax << "at " << __FILE__ << __LINE__;
}
else
{
......@@ -105,7 +108,7 @@ namespace qmapcontrol
// TODO Error is currently undetected
//qDebug() << "NETWORK_PIXMAP_ERROR: " << ax;
qDebug() << "QMapControl external library: ERROR loading map:" << "width:" << pm.width() << "heigh:" << pm.height() << "at " << __FILE__ << __LINE__;
//qDebug() << "HTML ERROR MESSAGE:" << ax << "at " << __FILE__ << __LINE__;
qDebug() << "QMapControl: HTML ERROR MESSAGE:" << ax << "at " << __FILE__ << __LINE__;
}
}
......
......@@ -85,6 +85,7 @@
<file>images/earth.html</file>
<file>images/mapproviders/googleearth.svg</file>
<file>images/contrib/slugs.png</file>
<file>images/style-outdoor.css</file>
</qresource>
<qresource prefix="/general">
<file alias="vera.ttf">images/Vera.ttf</file>
......
......@@ -47,33 +47,35 @@ DEFINES += _TTY_NOWARN_
# MAC OS X
macx {
COMPILER_VERSION = $$system(gcc -v)
# COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION)
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" ) {
CONFIG += x86 cocoa phonon
CONFIG -= x86_64
#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" ) {
# x86 Mac OS X Leopard 10.5 and earlier
CONFIG += x86 x86_64 cocoa phonon
#CONFIG -= x86_64
#message(Building for Mac OS X 32bit/Leopard 10.5 and earlier)
# Enable function-profiling with the OS X saturn tool
debug {
#debug {
#QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn
CONFIG += console
}
} else {
# CONFIG += console
#}
#} else {
# x64 Mac OS X Snow Leopard 10.6 and later
CONFIG += x86_64 x86 cocoa phonon
# CONFIG += x86_64 x86 cocoa phonon
#CONFIG -= x86 # phonon
#message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
debug {
# debug {
#QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn
CONFIG += console
}
}
# }
#}
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5
......
......@@ -157,7 +157,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/mission/QGCCustomWaypointAction.ui \
src/ui/QGCUDPLinkConfiguration.ui
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui
INCLUDEPATH += src \
src/ui \
......@@ -268,7 +269,8 @@ HEADERS += src/MG.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
......@@ -394,7 +396,8 @@ SOURCES += src/main.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
......@@ -151,10 +151,14 @@ GAudioOutput::~GAudioOutput()
void GAudioOutput::mute(bool mute)
{
this->muted = mute;
QSettings settings;
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", this->muted);
settings.sync();
if (mute != muted)
{
this->muted = mute;
QSettings settings;
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", this->muted);
settings.sync();
emit mutedChanged(muted);
}
}
bool GAudioOutput::isMuted()
......
......@@ -80,6 +80,9 @@ public:
VOICE_FEMALE
} QGVoice;
/** @brief Get the mute state */
bool isMuted();
public slots:
/** @brief Say this text if current output priority matches */
bool say(QString text, int severity=1);
......@@ -101,8 +104,9 @@ public slots:
void notifyNegative();
/** @brief Mute/unmute sound */
void mute(bool mute);
/** @brief Get the mute state */
bool isMuted();
signals:
void mutedChanged(bool);
protected:
#ifdef Q_OS_MAC
......
......@@ -37,6 +37,15 @@ quint64 groundTimeUsecs()
return static_cast<quint64>(microseconds + (time.time().msec()*1000));
}
quint64 groundTimeMilliseconds()
{
QDateTime time = QDateTime::currentDateTime();
time = time.toUTC();
/* Return seconds and milliseconds, in milliseconds unit */
quint64 seconds = time.toTime_t() * static_cast<quint64>(1000);
return static_cast<quint64>(seconds + (time.time().msec()));
}
float limitAngleToPMPIf(float angle)
{
while (angle > ((float)M_PI+FLT_EPSILON))
......
......@@ -16,11 +16,15 @@ namespace QGC
const QColor colorRed(154, 20, 20);
const QColor colorGreen(20, 200, 20);
const QColor colorYellow(255, 255, 0);
const QColor colorOrange(255, 140, 0);
const QColor colorDarkYellow(180, 180, 0);
const QColor colorBackground("#050508");
const QColor colorBlack(0, 0, 0);
/** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs();
/** @brief Get the current ground time in milliseconds */
quint64 groundTimeMilliseconds();
/** @brief Returns the angle limited to -pi - pi */
float limitAngleToPMPIf(float angle);
/** @brief Returns the angle limited to -pi - pi */
......
......@@ -32,7 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include <QStringList>
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _yaw, bool _autocontinue, bool _current, double _orbit, int _holdTime, MAV_FRAME _frame, MAV_COMMAND _action)
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _yaw, bool _autocontinue, bool _current, double _orbit, int _holdTime, MAV_FRAME _frame, MAV_CMD _action)
: id(_id),
x(_x),
y(_y),
......@@ -61,11 +61,10 @@ void Waypoint::save(QTextStream &saveStream)
position = position.arg(y, 0, 'g', 18);
position = position.arg(z, 0, 'g', 18);
QString parameters("%1\t%2\t%3\t%4");
parameters = parameters.arg(param1, 0, 'g', 18);
parameters = parameters.arg(param2, 0, 'g', 18);
parameters = parameters.arg(orbit, 0, 'g', 18);
parameters = parameters.arg(yaw, 0, 'g', 18);
saveStream << this->getId() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << this->getCurrent() << "\t" << position << "\t" << this->getAutoContinue() << "\r\n";
parameters = parameters.arg(param1, 0, 'g', 18).arg(param2, 0, 'g', 18).arg(orbit, 0, 'g', 18).arg(yaw, 0, 'g', 18);
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE>
// as documented here: http://qgroundcontrol.org/waypoint_protocol
saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n";
}
bool Waypoint::load(QTextStream &loadStream)
......@@ -74,13 +73,13 @@ bool Waypoint::load(QTextStream &loadStream)
if (wpParams.size() == 12)
{
this->id = wpParams[0].toInt();
this->frame = (MAV_FRAME) wpParams[1].toInt();
this->action = (MAV_COMMAND) wpParams[2].toInt();
this->param1 = wpParams[3].toDouble();
this->param2 = wpParams[4].toDouble();
this->orbit = wpParams[5].toDouble();
this->yaw = wpParams[6].toDouble();
this->current = (wpParams[7].toInt() == 1 ? true : false);
this->current = (wpParams[1].toInt() == 1 ? true : false);
this->frame = (MAV_FRAME) wpParams[2].toInt();
this->action = (MAV_CMD) wpParams[3].toInt();
this->param1 = wpParams[4].toDouble();
this->param2 = wpParams[5].toDouble();
this->orbit = wpParams[6].toDouble();
this->yaw = wpParams[7].toDouble();
this->x = wpParams[8].toDouble();
this->y = wpParams[9].toDouble();
this->z = wpParams[10].toDouble();
......@@ -125,6 +124,33 @@ void Waypoint::setZ(double z)
}
}
void Waypoint::setLatitude(double lat)
{
if (this->x != lat)
{
this->x = lat;
emit changed(this);
}
}
void Waypoint::setLongitude(double lon)
{
if (this->y != lon)
{
this->y = lon;
emit changed(this);
}
}
void Waypoint::setAltitude(double altitude)
{
if (this->z != altitude)
{
this->z = altitude;
emit changed(this);
}
}
void Waypoint::setYaw(double yaw)
{
if (this->yaw != yaw)
......@@ -136,14 +162,14 @@ void Waypoint::setYaw(double yaw)
void Waypoint::setAction(int action)
{
if (this->action != (MAV_COMMAND)action)
if (this->action != (MAV_CMD)action)
{
this->action = (MAV_COMMAND)action;
this->action = (MAV_CMD)action;
emit changed(this);
}
}
void Waypoint::setAction(MAV_COMMAND action)
void Waypoint::setAction(MAV_CMD action)
{
if (this->action != action)
{
......
......@@ -45,13 +45,16 @@ class Waypoint : public QObject
public:
Waypoint(quint16 id = 0, double x = 0.0f, double y = 0.0f, double z = 0.0f, double yaw = 0.0f, bool autocontinue = false,
bool current = false, double orbit = 0.15f, int holdTime = 0,
MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_COMMAND action=MAV_CMD_NAV_WAYPOINT);
MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT);
~Waypoint();
quint16 getId() const { return id; }
double getX() const { return x; }
double getY() const { return y; }
double getZ() const { return z; }
double getLatitude() const { return x; }
double getLongitude() const { return y; }
double getAltitude() const { return z; }
double getYaw() const { return yaw; }
bool getAutoContinue() const { return autocontinue; }
bool getCurrent() const { return current; }
......@@ -67,7 +70,7 @@ public:
double getParam7() const { return z; }
int getTurns() const { return param1; }
MAV_FRAME getFrame() const { return frame; }
MAV_COMMAND getAction() const { return action; }
MAV_CMD getAction() const { return action; }
const QString& getName() const { return name; }
void save(QTextStream &saveStream);
......@@ -81,7 +84,7 @@ protected:
double z;
double yaw;
MAV_FRAME frame;
MAV_COMMAND action;
MAV_CMD action;
bool autocontinue;
bool current;
double orbit;
......@@ -95,10 +98,13 @@ public slots:
void setX(double x);
void setY(double y);
void setZ(double z);
void setLatitude(double lat);
void setLongitude(double lon);
void setAltitude(double alt);
void setYaw(double yaw);
/** @brief Set the waypoint action */
void setAction(int action);
void setAction(MAV_COMMAND action);
void setAction(MAV_CMD action);
void setFrame(MAV_FRAME frame);
void setAutocontinue(bool autoContinue);
void setCurrent(bool current);
......
......@@ -62,6 +62,9 @@ public:
/** @brief Get a list of all links */
const QList<LinkInterface*> getLinks();
/** @brief Get a list of all protocols */
const QList<ProtocolInterface*> getProtocols() { return protocolLinks.uniqueKeys(); }
public slots:
void add(LinkInterface* link);
......
......@@ -44,6 +44,11 @@ MAVLinkProtocol::MAVLinkProtocol() :
m_loggingEnabled(false),
m_logfile(NULL),
m_enable_version_check(true),
m_paramRetransmissionTimeout(350),
m_paramRewriteTimeout(500),
m_paramGuardEnabled(true),
m_actionGuardEnabled(false),
m_actionRetransmissionTimeout(100),
versionMismatchIgnore(false),
systemId(QGC::defaultSystemId)
{
......@@ -95,6 +100,14 @@ void MAVLinkProtocol::loadSettings()
{
systemId = temp;
}
// Parameter interface settings
bool ok;
temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout).toInt(&ok);
if (ok) m_paramRetransmissionTimeout = temp;
temp = settings.value("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout).toInt(&ok);
if (ok) m_paramRewriteTimeout = temp;
m_paramGuardEnabled = settings.value("PARAMETER_TRANSMISSION_GUARD_ENABLED", m_paramGuardEnabled).toBool();
settings.endGroup();
}
......@@ -113,6 +126,10 @@ void MAVLinkProtocol::storeSettings()
// Logfile exists, store the name
settings.setValue("LOGFILE_NAME", m_logfile->fileName());
}
// Parameter interface settings
settings.setValue("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout);
settings.setValue("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout);
settings.setValue("PARAMETER_TRANSMISSION_GUARD_ENABLED", m_paramGuardEnabled);
settings.endGroup();
settings.sync();
//qDebug() << "Storing settings!";
......@@ -418,6 +435,51 @@ void MAVLinkProtocol::enableMultiplexing(bool enabled)
if (changed) emit multiplexingChanged(m_multiplexingEnabled);
}
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
if (enabled != m_paramGuardEnabled)
{
m_paramGuardEnabled = enabled;
emit paramGuardChanged(m_paramGuardEnabled);
}
}
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
if (enabled != m_actionGuardEnabled)
{
m_actionGuardEnabled = enabled;
emit actionGuardChanged(m_actionGuardEnabled);
}
}
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
if (ms != m_paramRetransmissionTimeout)
{
m_paramRetransmissionTimeout = ms;
emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
}
}
void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
if (ms != m_paramRewriteTimeout)
{
m_paramRewriteTimeout = ms;
emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
}
}
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
if (ms != m_actionRetransmissionTimeout)
{
m_actionRetransmissionTimeout = ms;
emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
}
}
void MAVLinkProtocol::enableLogging(bool enabled)
{
bool changed = false;
......
......@@ -77,6 +77,16 @@ public:
int getVersion() { return MAVLINK_VERSION; }
/** @brief Get the name of the packet log file */
QString getLogfileName();
/** @brief Get state of parameter retransmission */
bool paramGuardEnabled() { return m_paramGuardEnabled; }
/** @brief Get parameter read timeout */
int getParamRetransmissionTimeout() { return m_paramRetransmissionTimeout; }
/** @brief Get parameter write timeout */
int getParamRewriteTimeout() { return m_paramRewriteTimeout; }
/** @brief Get state of action retransmission */
bool actionGuardEnabled() { return m_actionGuardEnabled; }
/** @brief Get parameter read timeout */
int getActionRetransmissionTimeout() { return m_actionRetransmissionTimeout; }
public slots:
/** @brief Receive bytes from a communication interface */
......@@ -99,6 +109,21 @@ public slots:
/** @brief Enabled/disable packet multiplexing */
void enableMultiplexing(bool enabled);
/** @brief Enable / disable parameter retransmission */
void enableParamGuard(bool enabled);
/** @brief Enable / disable action retransmission */
void enableActionGuard(bool enabled);
/** @brief Set parameter read timeout */
void setParamRetransmissionTimeout(int ms);
/** @brief Set parameter write timeout */
void setParamRewriteTimeout(int ms);
/** @brief Set parameter read timeout */
void setActionRetransmissionTimeout(int ms);
/** @brief Set log file name */
void setLogfileName(const QString& filename);
......@@ -121,6 +146,11 @@ protected:
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
QFile* m_logfile; ///< Logfile
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
int m_paramRetransmissionTimeout; ///< Timeout for parameter retransmission
int m_paramRewriteTimeout; ///< Timeout for sending re-write request
bool m_paramGuardEnabled; ///< Parameter retransmission/rewrite enabled
bool m_actionGuardEnabled; ///< Action request retransmission enabled
int m_actionRetransmissionTimeout; ///< Timeout for parameter retransmission
QMutex receiveMutex; ///< Mutex to protect receiveBytes function
int lastIndex[256][256];
int totalReceiveCounter;
......@@ -143,6 +173,18 @@ signals:
void versionCheckChanged(bool enabled);
/** @brief Emitted if a message from the protocol should reach the user */
void protocolStatusMessage(const QString& title, const QString& message);
/** @brief Emitted if a new system ID was set */
void systemIdChanged(int systemId);
/** @brief Emitted if param guard status changed */
void paramGuardChanged(bool enabled);
/** @brief Emitted if param read timeout changed */
void paramRetransmissionTimeoutChanged(int ms);
/** @brief Emitted if param write timeout changed */
void paramRewriteTimeoutChanged(int ms);
/** @brief Emitted if action guard status changed */
void actionGuardChanged(bool enabled);
/** @brief Emitted if actiion request timeout changed */
void actionRetransmissionTimeoutChanged(int ms);
};
#endif // MAVLINKPROTOCOL_H_
......@@ -817,8 +817,8 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
mavlink_param_request_list_t read;
mavlink_msg_param_request_list_decode(&msg, &read);
if (read.target_system == systemId)
{
// if (read.target_system == systemId)
// {
// Output all params
// Iterate through all components, through all parameters and emit them
QMap<QString, float>::iterator i;
......@@ -826,27 +826,33 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
int j = 0;
for (i = onboardParams.begin(); i != onboardParams.end(); ++i)
{
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)i.key().toStdString().c_str(), i.value(), onboardParams.size(), j);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer+=bufferlength;
if (j != 5)
{
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)i.key().toStdString().c_str(), i.value(), onboardParams.size(), j);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer+=bufferlength;
}
j++;
}
qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
}
// }
}
break;
case MAVLINK_MSG_ID_PARAM_SET:
{
qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER";
mavlink_param_set_t set;
mavlink_msg_param_set_decode(&msg, &set);
if (set.target_system == systemId)
// Drop on even milliseconds
if (QGC::groundTimeMilliseconds() % 2 == 0)
{
qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER";
mavlink_param_set_t set;
mavlink_msg_param_set_decode(&msg, &set);
// if (set.target_system == systemId)
// {
QString key = QString((char*)set.param_id);
if (onboardParams.contains(key))
{
......@@ -854,13 +860,50 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(systemId, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value, onboardParams.size(), 0);
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer+=bufferlength;
}
// }
}
}
break;
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
{
qDebug() << "SIMULATION RECEIVED COMMAND TO SEND PARAMETER";
mavlink_param_request_read_t read;
mavlink_msg_param_request_read_decode(&msg, &read);
QByteArray bytes((char*)read.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
QString key = QString(bytes);
if (onboardParams.contains(key))
{
float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
// 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() << "Sending PARAM" << key;
}
else if (read.param_index < onboardParams.size())
{
key = onboardParams.keys().at(read.param_index);
float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
// 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() << "Sending PARAM #ID" << (read.param_index) << "KEY:" << key;
}
}
break;
......@@ -868,10 +911,10 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
//unsigned char v=data[i];
//fprintf(stderr,"%02x ", v);
unsigned char v=data[i];
fprintf(stderr,"%02x ", v);
}
//fprintf(stderr,"\n");
fprintf(stderr,"\n");
readyBufferMutex.lock();
for (int i = 0; i < streampointer; i++)
......@@ -903,22 +946,22 @@ void MAVLinkSimulationLink::readBytes() {
readyBufferMutex.unlock();
// if (len > 0)
// {
// qDebug() << "Simulation sent " << len << " bytes to groundstation: ";
//
// /* Increase write counter */
// //bitsSentTotal += size * 8;
//
// //Output all bytes as hex digits
// int i;
// for (i=0; i<len; i++)
// {
// unsigned int v=data[i];
// fprintf(stderr,"%02x ", v);
// }
// fprintf(stderr,"\n");
// }
// if (len > 0)
// {
// qDebug() << "Simulation sent " << len << " bytes to groundstation: ";
// /* Increase write counter */
// //bitsSentTotal += size * 8;
// //Output all bytes as hex digits
// int i;
// for (i=0; i<len; i++)
// {
// unsigned int v=data[i];
// fprintf(stderr,"%02x ", v);
// }
// fprintf(stderr,"\n");
// }
}
/**
......@@ -957,8 +1000,9 @@ bool MAVLinkSimulationLink::connect()
start(LowPriority);
MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 47.376, 8.548);
//MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2);
Q_UNUSED(mav1);
//MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2);
//
//Q_UNUSED(mav2);
// timer->start(rate);
return true;
......
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include "MAVLinkSimulationMAV.h"
......@@ -14,8 +15,8 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
latitude(lat),
longitude(lon),
altitude(0.0),
x(lon),
y(lat),
x(lat),
y(lon),
z(550),
roll(0.0),
pitch(0.0),
......@@ -95,7 +96,7 @@ void MAVLinkSimulationMAV::mainloop()
{
//float trueyaw = atan2f(xm, ym);
float newYaw = atan2f(xm, ym);
float newYaw = atan2f(ym, xm);
if (fabs(yaw - newYaw) < 90)
{
......@@ -111,8 +112,8 @@ void MAVLinkSimulationMAV::mainloop()
//if (sqrt(xm*xm+ym*ym) > 0.0000001)
if (flying)
{
x += sin(yaw)*radPer100ms;
y += cos(yaw)*radPer100ms;
x += cos(yaw)*radPer100ms;
y += sin(yaw)*radPer100ms;
z += altPer100ms*zsign;
}
......@@ -132,9 +133,9 @@ void MAVLinkSimulationMAV::mainloop()
mavlink_message_t msg;
mavlink_global_position_int_t pos;
pos.alt = z*1000.0;
pos.lat = y*1E7;
pos.lon = x*1E7;
pos.vx = 10.0f*100.0f;
pos.lat = x*1E7;
pos.lon = y*1E7;
pos.vx = sin(yaw)*10.0f*100.0f;
pos.vy = 0;
pos.vz = altPer100ms*10.0f*100.0f*zsign*-1.0f;
mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos);
......@@ -143,9 +144,13 @@ void MAVLinkSimulationMAV::mainloop()
// ATTITUDE
mavlink_attitude_t attitude;
attitude.usec = 0;
attitude.roll = 0.0f;
attitude.pitch = 0.0f;
attitude.yaw = yaw;
attitude.rollspeed = 0.0f;
attitude.pitchspeed = 0.0f;
attitude.yawspeed = 0.0f;
mavlink_msg_attitude_encode(systemid, MAV_COMP_ID_IMU, &msg, &attitude);
link->sendMAVLinkMessage(&msg);
......@@ -158,18 +163,18 @@ void MAVLinkSimulationMAV::mainloop()
status.packet_drop = 0;
status.vbat = 10500;
status.status = sys_state;
status.battery_remaining = 912;
mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
link->sendMAVLinkMessage(&msg);
timer10Hz = 5;
// VFR HUD
mavlink_vfr_hud_t hud;
hud.airspeed = pos.vx;
hud.groundspeed = pos.vx;
hud.alt = pos.alt;
hud.airspeed = pos.vx/100.0f;
hud.groundspeed = pos.vx/100.0f;
hud.alt = z;
hud.heading = static_cast<int>((yaw/M_PI)*180.0f+180.0f) % 360;
hud.climb = pos.vz;
hud.climb = pos.vz/100.0f;
hud.throttle = 90;
mavlink_msg_vfr_hud_encode(systemid, MAV_COMP_ID_IMU, &msg, &hud);
link->sendMAVLinkMessage(&msg);
......@@ -183,8 +188,19 @@ void MAVLinkSimulationMAV::mainloop()
nav.wp_dist = 2.0f;
nav.alt_error = 0.5f;
nav.xtrack_error = 0.2f;
nav.aspd_error = 0.0f;
mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav);
link->sendMAVLinkMessage(&msg);
// RAW PRESSURE
mavlink_raw_pressure_t pressure;
pressure.press_abs = 1000;
pressure.press_diff1 = 2000;
pressure.press_diff2 = 5000;
pressure.temperature = 18150; // 18.15 deg Celsius
pressure.usec = 0; // Works also with zero timestamp
mavlink_msg_raw_pressure_encode(systemid, MAV_COMP_ID_IMU, &msg, &pressure);
link->sendMAVLinkMessage(&msg);
}
// 25 Hz execution
......@@ -203,6 +219,7 @@ void MAVLinkSimulationMAV::mainloop()
control_status.gps_fix = 2; // 2D GPS fix
control_status.position_fix = 3; // 3D fix from GPS + barometric pressure
control_status.vision_fix = 0; // no fix from vision system
control_status.ahrs_health = 230;
mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status);
link->sendMAVLinkMessage(&ret);
#endif //MAVLINK_ENABLED_PIXHAWK
......@@ -300,21 +317,26 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
mavlink_msg_action_decode(&msg, &action);
if (systemid == action.target && (action.target_component == 0 || action.target_component == MAV_COMP_ID_IMU))
{
mavlink_action_ack_t ack;
ack.action = action.action;
switch (action.action)
{
case MAV_ACTION_TAKEOFF:
flying = true;
nav_mode = MAV_NAV_LIFTOFF;
ack.result = 1;
break;
default:
{
mavlink_statustext_t text;
mavlink_message_t r_msg;
sprintf((char*)text.text, "MAV%d ignored unknown action %d", systemid, action.action);
mavlink_msg_statustext_encode(systemid, MAV_COMP_ID_IMU, &r_msg, &text);
link->sendMAVLinkMessage(&r_msg);
ack.result = 0;
}
break;
}
// Give feedback about action
mavlink_message_t r_msg;
mavlink_msg_action_ack_encode(systemid, MAV_COMP_ID_IMU, &r_msg, &ack);
link->sendMAVLinkMessage(&r_msg);
}
}
break;
......@@ -324,6 +346,7 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
mavlink_msg_local_position_setpoint_set_decode(&msg, &sp);
if (sp.target_system == this->systemid)
{
nav_mode = MAV_NAV_WAYPOINT;
previousSPX = nextSPX;
previousSPY = nextSPY;
previousSPZ = nextSPZ;
......
......@@ -573,11 +573,11 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
mavlink_global_position_int_t pos;
mavlink_msg_global_position_int_decode(msg, &pos);
float x = static_cast<double>(pos.lon)/1E7;
float y = static_cast<double>(pos.lat)/1E7;
float z = static_cast<double>(pos.alt)/1000;
float x = static_cast<double>(pos.lat)/1E7;
float y = static_cast<double>(pos.lon)/1E7;
//float z = static_cast<double>(pos.alt)/1000;
qDebug() << "Received new position: x:" << x << "| y:" << y << "| z:" << z;
//qDebug() << "Received new position: x:" << x << "| y:" << y << "| z:" << z;
posReached = false;
yawReached = true;
......
......@@ -247,11 +247,11 @@ bool MAVLinkXMLParser::generate()
// Everything sane, starting with enum content
currEnum = "enum " + enumName.toUpper() + "\n{\n";
currEnumEnd = QString("\n%1_ENUM_END\n};\n\n").arg(enumName.toUpper());
currEnumEnd = QString("\t%1_ENUM_END\n};\n\n").arg(enumName.toUpper());
int nextEnumValue = 0;
// Get the message fields
// Get the enum fields
QDomNode f = e.firstChild();
while (!f.isNull())
{
......@@ -298,8 +298,9 @@ bool MAVLinkXMLParser::generate()
}
// Add the last parsed enum
// Remove the last comma, as the last value has none
int commaPosition = currEnum.lastIndexOf(",");
currEnum.remove(commaPosition, 1);
// ENUM END MARKER IS LAST ENTRY, COMMA REMOVAL NOT NEEDED
//int commaPosition = currEnum.lastIndexOf(",");
//currEnum.remove(commaPosition, 1);
enums += "/** @brief " + comment + " */\n" + currEnum + currEnumEnd;
} // Element is non-zero and element name is <enum>
......
......@@ -39,22 +39,12 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
// *nix (Linux, MacOS tested) serial port support
// port = new QextSerialPort(porthandle, QextSerialPort::Polling);
//port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
// port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
// port->setBaudRate(baudrate);
// port->setFlowControl(flow);
// port->setParity(parity);
// port->setDataBits(dataBits);
// port->setStopBits(stopBits);
// Set the port name
if (porthandle == "")
......@@ -103,7 +93,7 @@ void SerialLink::loadSettings()
settings.sync();
if (settings.contains("SERIALLINK_COMM_PORT"))
{
setPortName(settings.value("SERIALLINK_COMM_PORT").toString());
if (porthandle == "") setPortName(settings.value("SERIALLINK_COMM_PORT").toString());
setBaudRateType(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBits(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
......
......@@ -17,7 +17,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 0.8.3 (Alpha RC6)"
#define QGC_APPLICATION_VERSION "v. 0.8.3 (Alpha RC7)"
namespace QGC
......
......@@ -143,7 +143,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit errCountChanged(uasId, "IMU", "SPI0", status.spi0_err_count);
emit errCountChanged(uasId, "IMU", "SPI1", status.spi1_err_count);
emit errCountChanged(uasId, "IMU", "UART", status.uart_total_err_count);
emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "Load", "%", ((float)status.load)/10.0f, getUnixTime());
}
break;
default:
......
This diff is collapsed.
......@@ -124,11 +124,15 @@ protected: //COMMENTS FOR TEST UNIT
float emptyVoltage; ///< Voltage of the empty battery (0%)
float startVoltage; ///< Voltage at system start
float warnVoltage; ///< Voltage where QGC will start to warn about low battery
float warnLevelPercent; ///< Warning level, in percent
double currentVoltage; ///< Voltage currently measured
float lpVoltage; ///< Low-pass filtered voltage
bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
float chargeLevel; ///< Charge level of battery, in percent
int timeRemaining; ///< Remaining time calculated based on previous and current
unsigned int mode; ///< The current mode of the MAV
int mode; ///< The current mode of the MAV
int status; ///< The current status of the MAV
int navMode; ///< The current navigation mode of the MAV
quint64 onboardTimeOffset;
bool controlRollManual; ///< status flag, true if roll is controlled manually
......@@ -158,6 +162,16 @@ protected: //COMMENTS FOR TEST UNIT
double yaw;
quint64 lastHeartbeat; ///< Time of the last heartbeat message
QTimer* statusTimeout; ///< Timer for various status timeouts
int imageSize; ///< Image size being transmitted (bytes)
int imagePackets; ///< Number of data packets being sent for this image
int imagePacketsArrived; ///< Number of data packets recieved
int imagePayload; ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases.
int imageQuality; ///< JPEG-Quality of the transmitted image (percentage)
QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream
QImage image; ///< Image data of last completely transmitted image
quint64 imageStart;
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
......@@ -167,14 +181,18 @@ public:
/** @brief Estimate how much flight time is remaining */
int calculateTimeRemaining();
/** @brief Get the current charge level */
double getChargeLevel();
float getChargeLevel();
/** @brief Get the human-readable status message for this code */
void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
/** @brief Get the human-readable navigation mode translation for this mode */
QString getNavModeText(int mode);
/** @brief Check if vehicle is in autonomous mode */
bool isAuto();
UASWaypointManager* getWaypointManager() { return &waypointManager; }
int getSystemType();
QImage getImage();
void requestImage(); // ?
int getAutopilotType() {return autopilot;}
public slots:
......@@ -256,6 +274,9 @@ public slots:
/** @brief Request all parameters */
void requestParameters();
/** @brief Request a single parameter by index */
void requestParameter(int component, int parameter);
/** @brief Set a system parameter */
void setParameter(const int component, const QString& id, const float value);
......@@ -314,6 +335,8 @@ signals:
/** @brief Propagate a heartbeat received from the system */
void heartbeat(UASInterface* uas);
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
protected:
/** @brief Get the UNIX timestamp in milliseconds */
......
......@@ -226,6 +226,8 @@ public slots:
virtual void setLocalOriginAtCurrentGPSPosition() = 0;
/** @brief Request all onboard parameters of all components */
virtual void requestParameters() = 0;
/** @brief Request one specific onboard parameter */
virtual void requestParameter(int component, int parameter) = 0;
/** @brief Write parameter to permanent storage */
virtual void writeParametersToStorage() = 0;
/** @brief Read parameter from permanent storage */
......@@ -304,7 +306,11 @@ signals:
void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z);
void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2);
/** @brief A text message from the system has been received */
void textMessageReceived(int uasid, int componentid, int severity, QString text);
void navModeChanged(int uasid, int mode, const QString& text);
/**
* @brief Update the error count of a device
*
......@@ -369,6 +375,7 @@ signals:
void waypointReached(UASInterface* uas, int id);
void autoModeChanged(bool autoMode);
void parameterChanged(int uas, int component, QString parameterName, float value);
void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, float value);
void patternDetected(int uasId, QString patternPath, float confidence, bool detected);
void letterDetected(int uasId, QString letter, float confidence, bool detected);
/**
......
......@@ -138,8 +138,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id)
{
qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_COMMAND) wp->command;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_COMMAND) wp->command);
qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_CMD) wp->command;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypoint(lwp, false);
//get next waypoint
......@@ -236,6 +236,7 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
{
if (systemId == uas.getUASID() && compId == MAV_COMP_ID_WAYPOINTPLANNER)
{
// FIXME Petri
if (current_state == WP_SETCURRENT)
{
protocol_timer.stop();
......@@ -257,11 +258,12 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
}
}
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
//emit update to UI widgets
emit currentWaypointChanged(wpc->seq);
//qDebug() << "Updated waypoints list";
}
qDebug() << "new current waypoint" << wpc->seq;
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
//emit update to UI widgets
emit currentWaypointChanged(wpc->seq);
//qDebug() << "new current waypoint" << wpc->seq;
}
}
......
......@@ -67,7 +67,7 @@ DebugConsole::DebugConsole(QWidget *parent) :
// Hide sent text field - it is only useful after send has been hit
m_ui->sentText->setVisible(false);
// Hide auto-send checkbox
m_ui->specialCheckBox->setVisible(false);
//m_ui->specialCheckBox->setVisible(false);
// Make text area not editable
m_ui->receiveText->setReadOnly(true);
// Limit to 500 lines
......@@ -85,10 +85,10 @@ DebugConsole::DebugConsole(QWidget *parent) :
snapShotTimer.setInterval(snapShotInterval);
snapShotTimer.start();
// Set hex checkbox checked
m_ui->hexCheckBox->setChecked(!convertToAscii);
m_ui->mavlinkCheckBox->setChecked(filterMAVLINK);
m_ui->holdCheckBox->setChecked(autoHold);
// // Set hex checkbox checked
// m_ui->hexCheckBox->setChecked(!convertToAscii);
// m_ui->mavlinkCheckBox->setChecked(filterMAVLINK);
// m_ui->holdCheckBox->setChecked(autoHold);
// Get a list of all existing links
links = QList<LinkInterface*>();
......@@ -116,12 +116,10 @@ DebugConsole::DebugConsole(QWidget *parent) :
// Connect Checkbox
connect(m_ui->specialComboBox, SIGNAL(highlighted(QString)), this, SLOT(specialSymbolSelected(QString)));
// Set add button invisible if auto add checkbox is checked
connect(m_ui->specialCheckBox, SIGNAL(clicked(bool)), m_ui->addSymbolButton, SLOT(setHidden(bool)));
//connect(m_ui->specialCheckBox, SIGNAL(clicked(bool)), m_ui->addSymbolButton, SLOT(setHidden(bool)));
// Allow to send via return
connect(m_ui->sendText, SIGNAL(returnPressed()), this, SLOT(sendBytes()));
hold(false);
loadSettings();
// Warn user about not activated hold
......@@ -131,6 +129,12 @@ DebugConsole::DebugConsole(QWidget *parent) :
}
}
void DebugConsole::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
storeSettings();
}
DebugConsole::~DebugConsole()
{
storeSettings();
......@@ -146,16 +150,16 @@ void DebugConsole::loadSettings()
m_ui->specialComboBox->setCurrentIndex(settings.value("SPECIAL_SYMBOL", m_ui->specialComboBox->currentIndex()).toInt());
m_ui->specialCheckBox->setChecked(settings.value("SPECIAL_SYMBOL_CHECKBOX_STATE", m_ui->specialCheckBox->isChecked()).toBool());
hexModeEnabled(settings.value("HEX_MODE_ENABLED", m_ui->hexCheckBox->isChecked()).toBool());
MAVLINKfilterEnabled(settings.value("MAVLINK_FILTER_ENABLED", m_ui->mavlinkCheckBox->isChecked()).toBool());
setAutoHold(settings.value("AUTO_HOLD_ENABLED", m_ui->holdCheckBox->isChecked()).toBool());
MAVLINKfilterEnabled(settings.value("MAVLINK_FILTER_ENABLED", filterMAVLINK).toBool());
setAutoHold(settings.value("AUTO_HOLD_ENABLED", autoHold).toBool());
settings.endGroup();
// Update visibility settings
if (m_ui->specialCheckBox->isChecked())
{
m_ui->specialCheckBox->setVisible(true);
m_ui->addSymbolButton->setVisible(false);
}
// // Update visibility settings
// if (m_ui->specialCheckBox->isChecked())
// {
// m_ui->specialCheckBox->setVisible(true);
// m_ui->addSymbolButton->setVisible(false);
// }
}
void DebugConsole::storeSettings()
......@@ -166,8 +170,8 @@ void DebugConsole::storeSettings()
settings.setValue("SPECIAL_SYMBOL", m_ui->specialComboBox->currentIndex());
settings.setValue("SPECIAL_SYMBOL_CHECKBOX_STATE", m_ui->specialCheckBox->isChecked());
settings.setValue("HEX_MODE_ENABLED", m_ui->hexCheckBox->isChecked());
settings.setValue("MAVLINK_FILTER_ENABLED", m_ui->mavlinkCheckBox->isChecked());
settings.setValue("AUTO_HOLD_ENABLED", m_ui->holdCheckBox->isChecked());
settings.setValue("MAVLINK_FILTER_ENABLED", filterMAVLINK);
settings.setValue("AUTO_HOLD_ENABLED", autoHold);
settings.endGroup();
settings.sync();
//qDebug() << "Storing settings!";
......@@ -242,6 +246,11 @@ void DebugConsole::setAutoHold(bool hold)
this->hold(false);
m_ui->holdButton->setChecked(false);
}
// Set auto hold checkbox
if (m_ui->holdCheckBox->isChecked() != hold)
{
m_ui->holdCheckBox->setChecked(hold);
}
// Set new state
autoHold = hold;
}
......@@ -516,7 +525,7 @@ QString DebugConsole::bytesToSymbolNames(const QByteArray& b)
void DebugConsole::specialSymbolSelected(const QString& text)
{
Q_UNUSED(text);
m_ui->specialCheckBox->setVisible(true);
//m_ui->specialCheckBox->setVisible(true);
}
void DebugConsole::appendSpecialSymbol(const QString& text)
......@@ -763,7 +772,7 @@ void DebugConsole::setConnectionState(bool connected)
else
{
m_ui->connectButton->setText(tr("Connect"));
m_ui->receiveText->appendHtml(QString("<font color=\"%1\">%2</font>\n").arg(QGC::colorYellow.name(), tr("Link %1 is unconnected.").arg(currLink->getName())));
m_ui->receiveText->appendHtml(QString("<font color=\"%1\">%2</font>\n").arg(QGC::colorOrange.name(), tr("Link %1 is unconnected.").arg(currLink->getName())));
}
}
......
......@@ -101,6 +101,7 @@ public slots:
protected:
void changeEvent(QEvent *e);
void hideEvent(QHideEvent* event);
/** @brief Convert a symbol name to the byte representation */
QByteArray symbolNameToBytes(const QString& symbol);
/** @brief Convert a symbol byte to the name */
......
......@@ -50,6 +50,9 @@
<property name="toolTip">
<string>Ignore MAVLINK protocol messages in display</string>
</property>
<property name="statusTip">
<string>Ignore MAVLINK protocol messages in display</string>
</property>
<property name="text">
<string>Hide MAVLink</string>
</property>
......@@ -58,7 +61,10 @@
<item>
<widget class="QCheckBox" name="hexCheckBox">
<property name="toolTip">
<string>Display and send bytes in HEX representation</string>
<string>Display and enter bytes in HEX representation (e.g. 0xAA)</string>
</property>
<property name="statusTip">
<string>Display and enter bytes in HEX representation (e.g. 0xAA)</string>
</property>
<property name="text">
<string>HEX</string>
......
......@@ -104,6 +104,9 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
columns = 1;
this->setAutoFillBackground(true);
QPalette pal = palette();
pal.setColor(backgroundRole(), QGC::colorBlack);
setPalette(pal);
vwidth = 80.0f;
vheight = 80.0f;
......@@ -221,12 +224,14 @@ void HSIDisplay::renderOverlay()
// Draw orientation labels
// Translate and rotate coordinate frame
painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
painter.rotate((yaw/(M_PI))*180.0f);
const float yawDeg = ((yaw/M_PI)*180.0f);
int yawRotate = static_cast<int>(yawDeg) % 360;
painter.rotate(-yawRotate);
paintText(tr("N"), ringColor, 3.5f, - 1.0f, - baseRadius - 5.5f, &painter);
paintText(tr("S"), ringColor, 3.5f, - 1.0f, + baseRadius + 1.5f, &painter);
paintText(tr("E"), ringColor, 3.5f, + baseRadius + 2.0f, - 1.25f, &painter);
paintText(tr("E"), ringColor, 3.5f, + baseRadius + 3.0f, - 1.25f, &painter);
paintText(tr("W"), ringColor, 3.5f, - baseRadius - 5.5f, - 1.75f, &painter);
painter.rotate((-yaw/(M_PI))*180.0f);
painter.rotate(+yawRotate);
painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
// Draw center indicator
......@@ -323,7 +328,7 @@ void HSIDisplay::renderOverlay()
{
// Position
QString str;
str.sprintf("%05.2f lat %06.2f lon %06.2f alt", lat, lon, alt);
str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 5.0f, &painter);
paintText(str, Qt::white, 2.6f, 10, vheight - 5.0f, &painter);
}
......
......@@ -1309,7 +1309,7 @@ void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRat
// Text
QString label;
label.sprintf("< %06.2f", value);
label.sprintf("< %+06.2f", value);
paintText(label, defaultColor, 3.0f, xRef+width/2.0f, yRef+height-((scaledValue - minRate)/(maxRate-minRate))*height - 1.6f, painter);
}
......
......@@ -51,16 +51,44 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled());
m_ui->systemIdSpinBox->setValue(protocol->getSystemId());
m_ui->paramGuardCheckBox->setChecked(protocol->paramGuardEnabled());
m_ui->paramRetransmissionSpinBox->setValue(protocol->getParamRetransmissionTimeout());
m_ui->paramRewriteSpinBox->setValue(protocol->getParamRewriteTimeout());
m_ui->actionGuardCheckBox->setChecked(protocol->actionGuardEnabled());
m_ui->actionRetransmissionSpinBox->setValue(protocol->getActionRetransmissionTimeout());
// Connect actions
// Heartbeat
connect(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool)));
connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool)));
// Logging
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(bool)));
connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableLogging(bool)));
// Version check
connect(protocol, SIGNAL(versionCheckChanged(bool)), m_ui->versionCheckBox, SLOT(setChecked(bool)));
connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableVersionCheck(bool)));
// Logfile
connect(m_ui->logFileButton, SIGNAL(clicked()), this, SLOT(chooseLogfileName()));
// System ID
connect(protocol, SIGNAL(systemIdChanged(int)), m_ui->systemIdSpinBox, SLOT(setValue(int)));
connect(m_ui->systemIdSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setSystemId(int)));
// Multiplexing
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingCheckBox, SLOT(setChecked(bool)));
connect(m_ui->multiplexingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableMultiplexing(bool)));
// Parameter guard
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramGuardCheckBox, SLOT(setChecked(bool)));
connect(m_ui->paramGuardCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableParamGuard(bool)));
connect(protocol, SIGNAL(paramRetransmissionTimeoutChanged(int)), m_ui->paramRetransmissionSpinBox, SLOT(setValue(int)));
connect(m_ui->paramRetransmissionSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setParamRetransmissionTimeout(int)));
connect(protocol, SIGNAL(paramRewriteTimeoutChanged(int)), m_ui->paramRewriteSpinBox, SLOT(setValue(int)));
connect(m_ui->paramRewriteSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setParamRewriteTimeout(int)));
// Action guard
connect(protocol, SIGNAL(actionGuardChanged(bool)), m_ui->actionGuardCheckBox, SLOT(setChecked(bool)));
connect(m_ui->actionGuardCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableActionGuard(bool)));
connect(protocol, SIGNAL(actionRetransmissionTimeoutChanged(int)), m_ui->actionRetransmissionSpinBox, SLOT(setValue(int)));
connect(m_ui->actionRetransmissionSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setActionRetransmissionTimeout(int)));
// Update values
m_ui->versionLabel->setText(tr("MAVLINK_VERSION: %1").arg(protocol->getVersion()));
......@@ -69,26 +97,40 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
// Connect visibility updates
connect(protocol, SIGNAL(versionCheckChanged(bool)), m_ui->versionLabel, SLOT(setVisible(bool)));
m_ui->versionLabel->setVisible(protocol->versionCheckEnabled());
//connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), m_ui->versionSpacer, SLOT(setVisible(bool)));
//connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), m_ui->logFileSpacer, SLOT(setVisible(bool)));
// Logging visibility
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileLabel, SLOT(setVisible(bool)));
m_ui->logFileLabel->setVisible(protocol->loggingEnabled());
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileButton, SLOT(setVisible(bool)));
m_ui->logFileButton->setVisible(protocol->loggingEnabled());
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool)));
m_ui->multiplexingFilterCheckBox->setVisible(protocol->multiplexingEnabled());
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterLineEdit, SLOT(setVisible(bool)));
m_ui->multiplexingFilterLineEdit->setVisible(protocol->multiplexingEnabled());
// // Multiplexing visibility
// connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool)));
// m_ui->multiplexingFilterCheckBox->setVisible(protocol->multiplexingEnabled());
// connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterLineEdit, SLOT(setVisible(bool)));
// m_ui->multiplexingFilterLineEdit->setVisible(protocol->multiplexingEnabled());
// Param guard visibility
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRetransmissionSpinBox, SLOT(setVisible(bool)));
m_ui->paramRetransmissionSpinBox->setVisible(protocol->paramGuardEnabled());
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRetransmissionLabel, SLOT(setVisible(bool)));
m_ui->paramRetransmissionLabel->setVisible(protocol->paramGuardEnabled());
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRewriteSpinBox, SLOT(setVisible(bool)));
m_ui->paramRewriteSpinBox->setVisible(protocol->paramGuardEnabled());
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRewriteLabel, SLOT(setVisible(bool)));
m_ui->paramRewriteLabel->setVisible(protocol->paramGuardEnabled());
// Action guard visibility
connect(protocol, SIGNAL(actionGuardChanged(bool)), m_ui->actionRetransmissionSpinBox, SLOT(setVisible(bool)));
m_ui->actionRetransmissionSpinBox->setVisible(protocol->actionGuardEnabled());
connect(protocol, SIGNAL(actionGuardChanged(bool)), m_ui->actionRetransmissionLabel, SLOT(setVisible(bool)));
m_ui->actionRetransmissionLabel->setVisible(protocol->actionGuardEnabled());
// TODO implement filtering
// and then remove these two lines
m_ui->multiplexingFilterCheckBox->setVisible(false);
m_ui->multiplexingFilterLineEdit->setVisible(false);
// Update settings
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
// // Update settings
// m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
// m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
// m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
}
void MAVLinkSettingsWidget::updateLogfileName(const QString& fileName)
......@@ -132,7 +174,8 @@ MAVLinkSettingsWidget::~MAVLinkSettingsWidget()
void MAVLinkSettingsWidget::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);
switch (e->type()) {
switch (e->type())
{
case QEvent::LanguageChange:
m_ui->retranslateUi(this);
break;
......@@ -140,3 +183,9 @@ void MAVLinkSettingsWidget::changeEvent(QEvent *e)
break;
}
}
void MAVLinkSettingsWidget::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
protocol->storeSettings();
}
......@@ -24,6 +24,7 @@ public slots:
protected:
MAVLinkProtocol* protocol;
void changeEvent(QEvent *e);
void hideEvent(QHideEvent* event);
private:
Ui::MAVLinkSettingsWidget *m_ui;
......
......@@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>431</width>
<height>256</height>
<height>387</height>
</rect>
</property>
<property name="windowTitle">
......@@ -151,6 +151,143 @@
</property>
</widget>
</item>
<item row="11" column="0" colspan="3">
<widget class="QCheckBox" name="paramGuardCheckBox">
<property name="text">
<string>Enable retransmission of parameter read/write requests</string>
</property>
</widget>
</item>
<item row="12" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="13" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="12" column="1">
<widget class="QLabel" name="paramRetransmissionLabel">
<property name="text">
<string>Read request retransmission timeout</string>
</property>
</widget>
</item>
<item row="13" column="1">
<widget class="QLabel" name="paramRewriteLabel">
<property name="text">
<string>Write request retransmission timeout</string>
</property>
</widget>
</item>
<item row="12" column="2">
<widget class="QSpinBox" name="paramRetransmissionSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>50</number>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>50</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="13" column="2">
<widget class="QSpinBox" name="paramRewriteSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>50</number>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>50</number>
</property>
</widget>
</item>
<item row="14" column="0" colspan="3">
<widget class="QCheckBox" name="actionGuardCheckBox">
<property name="text">
<string>Enable retransmission of actions / commands</string>
</property>
</widget>
</item>
<item row="15" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="15" column="1">
<widget class="QLabel" name="actionRetransmissionLabel">
<property name="text">
<string>Action request retransmission timeout</string>
</property>
</widget>
</item>
<item row="15" column="2">
<widget class="QSpinBox" name="actionRetransmissionSpinBox">
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>20</number>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
......
This diff is collapsed.
......@@ -88,6 +88,18 @@ public:
static MainWindow* instance();
~MainWindow();
enum QGC_MAINWINDOW_STYLE
{
QGC_MAINWINDOW_STYLE_NATIVE,
QGC_MAINWINDOW_STYLE_INDOOR,
QGC_MAINWINDOW_STYLE_OUTDOOR
};
/** @brief Get current visual style */
int getStyle() { return currentStyle; }
/** @brief Get auto link reconnect setting */
bool autoReconnectEnabled() { return autoReconnect; }
public slots:
// /** @brief Store the mainwindow settings */
// void storeSettings();
......@@ -101,6 +113,9 @@ public slots:
/** @brief Shows an info message as popup or as widget */
void showInfoMessage(const QString& title, const QString& message);
/** @brief Show the application settings */
void showSettings();
/** @brief Add a communication link */
void addLink();
void addLink(LinkInterface* link);
void configure();
......@@ -139,32 +154,25 @@ public slots:
void reloadStylesheet();
/** @brief Let the user select the CSS style sheet */
void selectStylesheet();
/** @brief Automatically reconnect last link */
void enableAutoReconnect(bool enabled);
/** @brief Switch to native application style */
void loadNativeStyle();
/** @brief Switch to indoor mission style */
void loadIndoorStyle();
/** @brief Switch to outdoor mission style */
void loadOutdoorStyle();
/** @brief Load a specific style */
void loadStyle(QGC_MAINWINDOW_STYLE style);
/** @brief Add a custom tool widget */
void createCustomWidget();
void closeEvent(QCloseEvent* event);
/*
==========================================================
Potentially Deprecated
==========================================================
*/
// void loadWidgets();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
// /** @brief Load 3D map view */
// void load3DMapView();
// /** @brief Load 3D Google Earth view */
// void loadGoogleEarthView();
// /** @brief Load 3D view */
// void load3DView();
/**
* @brief Shows a Docked Widget based on the action sender
*
......@@ -340,6 +348,8 @@ protected:
void configureWindowName();
void loadSettings();
void storeSettings();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
......@@ -414,6 +424,8 @@ protected:
QString screenFileName;
QTimer* videoTimer;
QString styleFileName;
bool autoReconnect;
QGC_MAINWINDOW_STYLE currentStyle;
private:
Ui::MainWindow ui;
......
......@@ -60,17 +60,17 @@
</property>
<widget class="QMenu" name="menuPreferences">
<property name="title">
<string>Preferences</string>
<string>Display</string>
</property>
<addaction name="actionSelectStylesheet"/>
<addaction name="actionReloadStylesheet"/>
<addaction name="actionSettings"/>
</widget>
<addaction name="actionJoystick_Settings"/>
<addaction name="actionSimulate"/>
<addaction name="separator"/>
<addaction name="actionMuteAudioOutput"/>
<addaction name="actionJoystickSettings"/>
<addaction name="actionSettings"/>
<addaction name="menuPreferences"/>
<addaction name="separator"/>
<addaction name="actionExit"/>
......
......@@ -92,11 +92,24 @@ MapWidget::MapWidget(QWidget *parent) :
// Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer);
// mc->addLayer(gsatLayer);
// Zurich, ETH
int lastZoom = 16;
double lastLat = 47.376889;
double lastLon = 8.548056;
QSettings settings;
settings.beginGroup("QGC_MAPWIDGET");
lastLat = settings.value("LAST_LATITUDE", lastLat).toDouble();
lastLon = settings.value("LAST_LONGITUDE", lastLon).toDouble();
lastZoom = settings.value("LAST_ZOOM", lastZoom).toInt();
settings.endGroup();
// SET INITIAL POSITION AND ZOOM
// Set default zoom level
mc->setZoom(16);
// Zurich, ETH
mc->setView(QPointF(8.548056,47.376889));
mc->setZoom(lastZoom);
mc->setView(QPointF(lastLon, lastLat));
// Veracruz Mexico
//mc->setView(QPointF(-96.105208,19.138955));
......@@ -262,7 +275,7 @@ void MapWidget::goTo()
bool ok;
QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
QString("%1,%2").arg(mc->currentCoordinate().x()).arg(mc->currentCoordinate().y()), &ok);
QString("%1,%2").arg(mc->currentCoordinate().y()).arg(mc->currentCoordinate().x()), &ok);
if (ok && !text.isEmpty())
{
QStringList split = text.split(",");
......@@ -276,7 +289,7 @@ void MapWidget::goTo()
if (ok)
{
mc->setView(QPointF(latitude, longitude));
mc->setView(QPointF(longitude, latitude));
}
}
}
......@@ -326,9 +339,11 @@ void MapWidget::mapproviderSelected(QAction* action)
mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
overlay->setVisible(false);
// yahooActionOverlay->setEnabled(true);
}
else if (action == googleActionMap)
......@@ -417,7 +432,15 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
if (mav)
{
mav->getWaypointManager()->addWaypoint(new Waypoint(mav->getWaypointManager()->getWaypointList().count(), coordinate.x(), coordinate.y(), 0.0f, 0.0f, true));
double altitude = 0.0;
double yaw = 0.0;
int wpListCount = mav->getWaypointManager()->getWaypointList().count();
if (wpListCount > 0)
{
altitude = mav->getWaypointManager()->getWaypointList().at(wpListCount-1)->getAltitude();
yaw = mav->getWaypointManager()->getWaypointList().at(wpListCount-1)->getYaw();
}
mav->getWaypointManager()->addWaypoint(new Waypoint(wpListCount, coordinate.y(), coordinate.x(), altitude, yaw, true));
}
else
{
......@@ -472,8 +495,8 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
{
// Waypoint is new, a new icon is created
QPointF coordinate;
coordinate.setX(wp->getX());
coordinate.setY(wp->getY());
coordinate.setX(wp->getLongitude());
coordinate.setY(wp->getLatitude());
createWaypointGraphAtMap(wpindex, coordinate);
}
else
......@@ -483,8 +506,8 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
if(!waypointIsDrag)
{
QPointF coordinate;
coordinate.setX(wp->getX());
coordinate.setY(wp->getY());
coordinate.setX(wp->getLongitude());
coordinate.setY(wp->getLatitude());
Point* waypoint;
waypoint = wps.at(wpindex);
......@@ -624,8 +647,8 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
if (wps.size() > index)
{
Waypoint* wp = wps.at(index);
wp->setX(coordinate.x());
wp->setY(coordinate.y());
wp->setLatitude(coordinate.y());
wp->setLongitude(coordinate.x());
mav->getWaypointManager()->notifyOfChange(wp);
}
}
......@@ -844,8 +867,8 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
qmapcontrol::Point* p;
QPointF coordinate;
coordinate.setX(lat);
coordinate.setY(lon);
coordinate.setX(lon);
coordinate.setY(lat);
if (!uasIcons.contains(uas->getUASID()))
{
......@@ -880,7 +903,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// if (p)
// {
p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lat, lon));
p->setCoordinate(QPointF(lon, lat));
//p->setYaw(uas->getYaw());
// }
// Extend trail
......@@ -901,7 +924,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Sets the view to the interesting area
if (followgps->isChecked())
{
updatePosition(0, lat, lon);
updatePosition(0, lon, lat);
}
else
{
......@@ -982,6 +1005,14 @@ void MapWidget::showEvent(QShowEvent* event)
void MapWidget::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
QSettings settings;
settings.beginGroup("QGC_MAPWIDGET");
QPointF currentPos = mc->currentCoordinate();
settings.setValue("LAST_LATITUDE", currentPos.y());
settings.setValue("LAST_LONGITUDE", currentPos.x());
settings.setValue("LAST_ZOOM", mc->currentZoom());
settings.endGroup();
settings.sync();
}
......
......@@ -44,12 +44,6 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
m_ui(new Ui::parameterWidget)
{
m_ui->setupUi(this);
// Make sure the combo box is empty
// because else indices get messed up
//m_ui->vehicleComboBox->clear();
// Setup UI connections
//connect(m_ui->vehicleComboBox, SIGNAL(activated(int)), this, SLOT(selectUAS(int)));
// Get current MAV list
QList<UASInterface*> systems = UASManager::instance()->getUASList();
......@@ -84,8 +78,6 @@ void ParameterInterface::selectUAS(int index)
*/
void ParameterInterface::addUAS(UASInterface* uas)
{
//m_ui->vehicleComboBox->addItem(uas->getUASName());
QGCParamWidget* param = new QGCParamWidget(uas, this);
paramWidgets->insert(uas->getUASID(), param);
m_ui->stackedWidget->addWidget(param);
......
This diff is collapsed.
......@@ -34,6 +34,8 @@ This file is part of the QGROUNDCONTROL project
#include <QTreeWidget>
#include <QTreeWidgetItem>
#include <QMap>
#include <QLabel>
#include <QTimer>
#include "UASInterface.h"
......@@ -50,9 +52,13 @@ public:
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
void parameterChanged(int component, QString parametername, float value);
/** @brief Request a single parameter */
void requestParameter(int component, int parameter);
public slots:
/** @brief Add a component to the list */
void addComponent(int uas, int component, QString componentName);
/** @brief Add a parameter to the list with retransmission / safety checks */
void addParameter(int uas, int component, int paramCount, int paramId, QString parameterName, float value);
/** @brief Add a parameter to the list */
void addParameter(int uas, int component, QString parameterName, float value);
/** @brief Request list of parameters from MAV */
......@@ -74,15 +80,34 @@ public slots:
void saveParameters();
/** @brief Load parameters from a file */
void loadParameters();
/** @brief Check for missing parameters */
void retransmissionGuardTick();
protected:
UASInterface* mav; ///< The MAV this widget is controlling
QTreeWidget* tree; ///< The parameter tree
UASInterface* mav; ///< The MAV this widget is controlling
QTreeWidget* tree; ///< The parameter tree
QLabel* statusLabel; ///< Parameter transmission label
QMap<int, QTreeWidgetItem*>* components; ///< The list of components
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups
QMap<int, QMap<QString, float>* > changedValues; ///< Changed values
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QVector<bool> received; ///< Successfully received parameters
QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
QMap<int, QMap<QString, float>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission
int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
/** @brief Activate / deactivate parameter retransmission */
void setRetransmissionGuardEnabled(bool enabled);
/** @brief Load settings */
void loadSettings();
};
#endif // QGCPARAMWIDGET_H
......@@ -97,7 +97,7 @@ void QGCRemoteControlView::setUASId(int id)
{
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIRawChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
......@@ -116,9 +116,7 @@ void QGCRemoteControlView::setUASId(int id)
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
......@@ -205,6 +203,8 @@ void QGCRemoteControlView::redraw()
{
progressBars.at(i)->setValue(normalized.at(i)*100.0f);
}
// Update RSSI
rssiBar->setValue(rssi*100);
updated = false;
}
}
......
......@@ -37,6 +37,7 @@ QGCSensorSettingsWidget::QGCSensorSettingsWidget(UASInterface* uas, QWidget *par
ui(new Ui::QGCSensorSettingsWidget)
{
ui->setupUi(this);
// FIXME James Goppert
// XXX: This might be a bad idea sending a message every time the value changes
connect(ui->spinBox_rawSensor, SIGNAL(valueChanged(int)), mav, SLOT(enableRawSensorDataTransmission(int)));
connect(ui->spinBox_controller, SIGNAL(valueChanged(int)), mav, SLOT(enableRawControllerDataTransmission(int)));
......
#include <QSettings>
#include "QGCSettingsWidget.h"
#include "MainWindow.h"
#include "ui_QGCSettingsWidget.h"
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
#include "GAudioOutput.h"
//, Qt::WindowFlags flags
QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) :
QDialog(parent, flags),
ui(new Ui::QGCSettingsWidget)
{
ui->setupUi(this);
// Add all protocols
QList<ProtocolInterface*> protocols = LinkManager::instance()->getProtocols();
foreach (ProtocolInterface* protocol, protocols)
{
MAVLinkProtocol* mavlink = dynamic_cast<MAVLinkProtocol*>(protocol);
if (mavlink)
{
MAVLinkSettingsWidget* msettings = new MAVLinkSettingsWidget(mavlink, this);
ui->tabWidget->addTab(msettings, "MAVLink");
}
}
this->window()->setWindowTitle(tr("QGroundControl Settings"));
// Audio preferences
ui->audioMuteCheckBox->setChecked(GAudioOutput::instance()->isMuted());
connect(ui->audioMuteCheckBox, SIGNAL(toggled(bool)), GAudioOutput::instance(), SLOT(mute(bool)));
connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), ui->audioMuteCheckBox, SLOT(setChecked(bool)));
// Reconnect
ui->reconnectCheckBox->setChecked(MainWindow::instance()->autoReconnectEnabled());
connect(ui->reconnectCheckBox, SIGNAL(clicked(bool)), MainWindow::instance(), SLOT(enableAutoReconnect(bool)));
// Style
MainWindow::QGC_MAINWINDOW_STYLE style = (MainWindow::QGC_MAINWINDOW_STYLE)MainWindow::instance()->getStyle();
switch (style)
{
case MainWindow::QGC_MAINWINDOW_STYLE_NATIVE:
ui->nativeStyle->setChecked(true);
break;
case MainWindow::QGC_MAINWINDOW_STYLE_INDOOR:
ui->indoorStyle->setChecked(true);
break;
case MainWindow::QGC_MAINWINDOW_STYLE_OUTDOOR:
ui->outdoorStyle->setChecked(true);
break;
}
connect(ui->nativeStyle, SIGNAL(clicked()), MainWindow::instance(), SLOT(loadNativeStyle()));
connect(ui->indoorStyle, SIGNAL(clicked()), MainWindow::instance(), SLOT(loadIndoorStyle()));
connect(ui->outdoorStyle, SIGNAL(clicked()), MainWindow::instance(), SLOT(loadOutdoorStyle()));
// Close / destroy
connect(ui->buttonBox, SIGNAL(accepted()), this, SLOT(deleteLater()));
// Set layout options
ui->generalPaneGridLayout->setAlignment(Qt::AlignTop);
}
QGCSettingsWidget::~QGCSettingsWidget()
{
delete ui;
}
#ifndef QGCSETTINGSWIDGET_H
#define QGCSETTINGSWIDGET_H
#include <QDialog>
namespace Ui {
class QGCSettingsWidget;
}
class QGCSettingsWidget : public QDialog
{
Q_OBJECT
public:
QGCSettingsWidget(QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet);
~QGCSettingsWidget();
public slots:
private:
Ui::QGCSettingsWidget *ui;
};
#endif // QGCSETTINGSWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCSettingsWidget</class>
<widget class="QDialog" name="QGCSettingsWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>535</width>
<height>427</height>
</rect>
</property>
<property name="windowTitle">
<string>Dialog</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QTabWidget" name="tabWidget">
<widget class="QWidget" name="general">
<attribute name="title">
<string>General</string>
</attribute>
<attribute name="toolTip">
<string>General Settings</string>
</attribute>
<layout class="QGridLayout" name="generalPaneGridLayout">
<item row="0" column="0">
<widget class="QCheckBox" name="audioMuteCheckBox">
<property name="text">
<string>Mute all audio output</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/audio-volume-muted.svg</normaloff>:/images/status/audio-volume-muted.svg</iconset>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QCheckBox" name="reconnectCheckBox">
<property name="text">
<string>Automatically reconnect last link on application startup</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QRadioButton" name="nativeStyle">
<property name="text">
<string>Use native platform look and feel (Windows/Linux/Mac OS)</string>
</property>
<property name="autoExclusive">
<bool>true</bool>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QRadioButton" name="indoorStyle">
<property name="text">
<string>Use indoor mission style (black background)</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QRadioButton" name="outdoorStyle">
<property name="text">
<string>Use outdoor mission style (light background)</string>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<widget class="QDialogButtonBox" name="buttonBox">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="standardButtons">
<set>QDialogButtonBox::Close</set>
</property>
</widget>
</item>
</layout>
</widget>
<resources>
<include location="../../mavground.qrc"/>
</resources>
<connections>
<connection>
<sender>buttonBox</sender>
<signal>accepted()</signal>
<receiver>QGCSettingsWidget</receiver>
<slot>accept()</slot>
<hints>
<hint type="sourcelabel">
<x>248</x>
<y>254</y>
</hint>
<hint type="destinationlabel">
<x>157</x>
<y>274</y>
</hint>
</hints>
</connection>
<connection>
<sender>buttonBox</sender>
<signal>rejected()</signal>
<receiver>QGCSettingsWidget</receiver>
<slot>reject()</slot>
<hints>
<hint type="sourcelabel">
<x>316</x>
<y>260</y>
</hint>
<hint type="destinationlabel">
<x>286</x>
<y>274</y>
</hint>
</hints>
</connection>
</connections>
</ui>
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>260</width>
<height>111</height>
<width>360</width>
<height>119</height>
</rect>
</property>
<property name="sizePolicy">
......@@ -56,10 +56,11 @@ QLabel#modeLabel {
QLabel#stateLabel {
font: 12px;
color: #3C7B9E;
}
QLabel#gpsLabel {
font: 8px;
QLabel#navLabel {
font: 12px;
}
QLabel#positionLabel {
......@@ -255,7 +256,7 @@ QMenu::separator {
<property name="title">
<string/>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="10,10,1,10,10,10,100,100">
<layout class="QGridLayout" name="gridLayout" columnstretch="1,1,10,10,10,10,80">
<property name="horizontalSpacing">
<number>4</number>
</property>
......@@ -306,23 +307,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="0" column="2" rowspan="8">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>4</width>
<height>88</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="3" colspan="3">
<item row="0" column="2" colspan="3">
<widget class="QLabel" name="nameLabel">
<property name="maximumSize">
<size>
......@@ -349,7 +334,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="0" column="6" colspan="2">
<item row="0" column="5" colspan="2">
<widget class="QLabel" name="modeLabel">
<property name="maximumSize">
<size>
......@@ -366,11 +351,11 @@ QMenu::separator {
</font>
</property>
<property name="text">
<string/>
<string>MODE</string>
</property>
</widget>
</item>
<item row="1" column="3" rowspan="3">
<item row="1" column="2" rowspan="3">
<widget class="QLabel" name="timeRemainingLabel">
<property name="font">
<font>
......@@ -391,7 +376,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="1" column="4" rowspan="3" colspan="2">
<item row="1" column="3" rowspan="3" colspan="2">
<widget class="QLabel" name="timeElapsedLabel">
<property name="font">
<font>
......@@ -412,7 +397,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="3" column="6" rowspan="2" colspan="2">
<item row="3" column="5" rowspan="2" colspan="2">
<widget class="QProgressBar" name="thrustBar">
<property name="font">
<font>
......@@ -430,7 +415,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="4" column="3">
<item row="4" column="2">
<widget class="QLabel" name="groundDistanceLabel">
<property name="font">
<font>
......@@ -451,7 +436,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="4" column="4" colspan="2">
<item row="4" column="3" colspan="2">
<widget class="QLabel" name="speedLabel">
<property name="font">
<font>
......@@ -536,22 +521,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="5" column="3" rowspan="2" colspan="2">
<widget class="QLabel" name="stateLabel">
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="7" column="3" colspan="2">
<item row="7" column="2">
<widget class="QLabel" name="waypointLabel">
<property name="font">
<font>
......@@ -575,7 +545,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="2" column="6" colspan="2">
<item row="2" column="5" colspan="2">
<widget class="QLabel" name="positionLabel">
<property name="minimumSize">
<size>
......@@ -608,25 +578,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="5" column="6" colspan="2">
<widget class="QLabel" name="statusTextLabel">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>12</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
</font>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="6" column="5" rowspan="2" colspan="3">
<item row="7" column="3" colspan="4">
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>4</number>
......@@ -791,6 +743,49 @@ QMenu::separator {
</item>
</layout>
</item>
<item row="5" column="2" rowspan="2" colspan="2">
<widget class="QLabel" name="navLabel">
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>NAV</string>
</property>
</widget>
</item>
<item row="8" column="0" colspan="7">
<widget class="QLabel" name="statusTextLabel">
<property name="text">
<string>Waiting for first status update..</string>
</property>
</widget>
</item>
<item row="5" column="5">
<widget class="QLabel" name="stateLabel">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>12</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>STATE</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
......
......@@ -188,7 +188,7 @@ void WaypointList::add()
else
{
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLongitude(), uas->getLatitude(), uas->getAltitude(), 0.0, true, true, 0.15, 0, MAV_FRAME_GLOBAL, MAV_CMD_NAV_WAYPOINT);
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0.0, true, true, 0.15, 0, MAV_FRAME_GLOBAL, MAV_CMD_NAV_WAYPOINT);
uas->getWaypointManager()->addWaypoint(wp);
}
}
......@@ -276,16 +276,38 @@ void WaypointList::waypointListChanged()
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
// Get all waypoints
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
// Store the current state, then check which widgets to update
// and which ones to delete
QList<Waypoint*> oldWaypoints = wpViews.keys();
if (!wpViews.empty())
{
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
viewIt.toFront();
while(viewIt.hasNext())
{
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
}
}
foreach (Waypoint* wp, waypoints)
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
// Create any new waypoint
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
{
WaypointView* wpview = new WaypointView(wp, this);
......@@ -295,30 +317,77 @@ void WaypointList::waypointListChanged()
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
else
{
// Update existing waypoints
// Mark as updated by removing from old list
oldWaypoints.removeAt(oldWaypoints.indexOf(wp));
listLayout->insertWidget(i, wpview);
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
}
// The old list now contains all wps to be deleted
foreach (Waypoint* wp, oldWaypoints)
{
// Delete waypoint view and entry in list
WaypointView* wpv = wpViews.value(wp);
if (wpv)
//check if ordering has changed
if(listLayout->itemAt(i)->widget() != wpv)
{
wpv->deleteLater();
listLayout->removeWidget(wpv);
listLayout->insertWidget(i, wpv);
}
wpViews.remove(wp);
wpv->updateValues(); // update the values of the ui elements in the view
}
this->setUpdatesEnabled(true);
loadFileGlobalWP = false;
}
}
//void WaypointList::waypointListChanged()
//{
// if (uas)
// {
// // Prevent updates to prevent visual flicker
// this->setUpdatesEnabled(false);
// // Get all waypoints
// const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
//// // Store the current state, then check which widgets to update
//// // and which ones to delete
//// QList<Waypoint*> oldWaypoints = wpViews.keys();
//// foreach (Waypoint* wp, waypoints)
//// {
//// WaypointView* wpview;
//// // Create any new waypoint
//// if (!wpViews.contains(wp))
//// {
//// wpview = new WaypointView(wp, this);
//// wpViews.insert(wp, wpview);
//// connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
//// connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
//// connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
//// connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
//// connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
//// listLayout->addWidget(wpview);
//// }
//// else
//// {
//// // Update existing waypoints
//// wpview = wpViews.value(wp);
//// }
//// // Mark as updated by removing from old list
//// oldWaypoints.removeAt(oldWaypoints.indexOf(wp));
//// wpview->updateValues(); // update the values of the ui elements in the view
//// }
//// // The old list now contains all wps to be deleted
//// foreach (Waypoint* wp, oldWaypoints)
//// {
//// // Delete waypoint view and entry in list
//// WaypointView* wpv = wpViews.value(wp);
//// if (wpv)
//// {
//// listLayout->removeWidget(wpv);
//// delete wpv;
//// }
//// wpViews.remove(wp);
//// }
// if (!wpViews.empty())
// {
......@@ -339,8 +408,11 @@ void WaypointList::waypointListChanged()
// if (i == waypoints.size())
// {
// WaypointView* widget = wpViews.find(cur).value();
// widget->hide();
// listLayout->removeWidget(widget);
// if (widget)
// {
// widget->hide();
// listLayout->removeWidget(widget);
// }
// wpViews.remove(cur);
// }
// }
......@@ -365,10 +437,10 @@ void WaypointList::waypointListChanged()
// listLayout->addWidget(wpv);
// }
this->setUpdatesEnabled(true);
}
loadFileGlobalWP = false;
}
// this->setUpdatesEnabled(true);
// }
//// loadFileGlobalWP = false;
//}
void WaypointList::moveUp(Waypoint* wp)
{
......
......@@ -24,6 +24,7 @@
WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
QWidget(parent),
customCommand(new Ui_QGCCustomWaypointAction),
viewMode(QGC_WAYPOINTVIEW_MODE_NAV),
m_ui(new Ui::WaypointView)
{
m_ui->setupUi(this);
......@@ -42,7 +43,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_action->addItem(tr("Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
m_ui->comboBox_action->addItem(tr("Return to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("Land"),MAV_CMD_NAV_LAND);
m_ui->comboBox_action->addItem(tr("Other"), MAV_COMMAND_ENUM_END);
m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
// m_ui->comboBox_action->addItem(tr("Delay"), MAV_ACTION_DELAY_BEFORE_COMMAND);
// m_ui->comboBox_action->addItem(tr("Ascend/Descent"), MAV_ACTION_ASCEND_AT_RATE);
// m_ui->comboBox_action->addItem(tr("Change Mode"), MAV_ACTION_CHANGE_MODE);
......@@ -75,8 +76,8 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(m_ui->posESpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->posDSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
connect(m_ui->lonSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->latSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->latSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->lonSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->altSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
//hidden degree to radian conversion of the yaw angle
......@@ -226,9 +227,9 @@ void WaypointView::changedAction(int index)
{
// set waypoint action
int actionIndex = m_ui->comboBox_action->itemData(index).toUInt();
if (actionIndex < MAV_COMMAND_ENUM_END && actionIndex >= 0)
if (actionIndex < MAV_CMD_ENUM_END && actionIndex >= 0)
{
MAV_COMMAND action = (MAV_COMMAND) actionIndex;
MAV_CMD action = (MAV_CMD) actionIndex;
wp->setAction(action);
}
......@@ -245,49 +246,34 @@ void WaypointView::changedAction(int index)
case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_NAV_LOITER_TIME:
case MAV_CMD_NAV_DELAY:
case MAV_CMD_SYS_SET_MODE:
// Back to global frame
if (wp->getFrame() == MAV_FRAME_MISSION) changedFrame(0);
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_DO_SET_MODE:
changeViewMode(QGC_WAYPOINTVIEW_MODE_NAV);
// Update frame view
updateFrameView(m_ui->comboBox_frame->currentIndex());
// Update view
updateActionView(actionIndex);
break;
case MAV_COMMAND_ENUM_END:
case MAV_CMD_ENUM_END:
default:
// Switch to mission frame
changedFrame(MAV_FRAME_MISSION);
wp->setFrame(MAV_FRAME_MISSION);
changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING);
break;
}
}
void WaypointView::updateFrameView(int frame)
void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
{
switch(frame)
switch (mode)
{
case MAV_FRAME_GLOBAL:
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
case MAV_FRAME_LOCAL:
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
case QGC_WAYPOINTVIEW_MODE_NAV:
case QGC_WAYPOINTVIEW_MODE_CONDITION:
// Hide everything, show condition widget
// TODO
case QGC_WAYPOINTVIEW_MODE_DO:
break;
case MAV_FRAME_MISSION:
case QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING:
// Hide almost everything
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
......@@ -301,7 +287,6 @@ void WaypointView::updateFrameView(int frame)
m_ui->latSpinBox->hide();
m_ui->lonSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->comboBox_frame->hide();
// Show action widget
if (!m_ui->customActionWidget->isVisible())
......@@ -313,6 +298,35 @@ void WaypointView::updateFrameView(int frame)
m_ui->autoContinue->show();
}
break;
}
}
void WaypointView::updateFrameView(int frame)
{
switch(frame)
{
case MAV_FRAME_GLOBAL:
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
case MAV_FRAME_LOCAL:
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
default:
std::cerr << "unknown frame" << std::endl;
}
......@@ -320,10 +334,11 @@ void WaypointView::updateFrameView(int frame)
void WaypointView::deleted(QObject* waypoint)
{
if (waypoint == this->wp)
{
deleteLater();
}
Q_UNUSED(waypoint);
// if (waypoint == this->wp)
// {
// deleteLater();
// }
}
void WaypointView::changedFrame(int index)
......@@ -389,13 +404,13 @@ void WaypointView::updateValues()
break;
case(MAV_FRAME_GLOBAL):
{
if (m_ui->lonSpinBox->value() != wp->getX())
if (m_ui->latSpinBox->value() != wp->getX())
{
m_ui->lonSpinBox->setValue(wp->getX());
m_ui->latSpinBox->setValue(wp->getX());
}
if (m_ui->latSpinBox->value() != wp->getY())
if (m_ui->lonSpinBox->value() != wp->getY())
{
m_ui->latSpinBox->setValue(wp->getY());
m_ui->lonSpinBox->setValue(wp->getY());
}
if (m_ui->altSpinBox->value() != wp->getZ())
{
......@@ -403,20 +418,18 @@ void WaypointView::updateValues()
}
}
break;
case (MAV_FRAME_MISSION):
{
// TODO Change to mission view
}
default:
// Do nothing
break;
}
// Update action
MAV_COMMAND action = wp->getAction();
MAV_CMD action = wp->getAction();
int action_index = m_ui->comboBox_action->findData(action);
// Set to "Other" action if it was -1
if (action_index == -1)
{
action_index = m_ui->comboBox_action->findData(MAV_COMMAND_ENUM_END);
action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
}
// Only update if changed
if (m_ui->comboBox_action->currentIndex() != action_index)
......@@ -516,14 +529,9 @@ void WaypointView::updateValues()
void WaypointView::setCurrent(bool state)
{
if (state)
{
m_ui->selectedBox->setCheckState(Qt::Checked);
}
else
{
m_ui->selectedBox->setCheckState(Qt::Unchecked);
}
m_ui->selectedBox->blockSignals(true);
m_ui->selectedBox->setChecked(state);
m_ui->selectedBox->blockSignals(false);
}
WaypointView::~WaypointView()
......
......@@ -37,6 +37,13 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include <iostream>
enum QGC_WAYPOINTVIEW_MODE {
QGC_WAYPOINTVIEW_MODE_NAV,
QGC_WAYPOINTVIEW_MODE_CONDITION,
QGC_WAYPOINTVIEW_MODE_DO,
QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING
};
namespace Ui {
class WaypointView;
}
......@@ -68,12 +75,16 @@ public slots:
void setYaw(int); //hidden degree to radian conversion
protected slots:
void changeViewMode(QGC_WAYPOINTVIEW_MODE mode);
protected:
virtual void changeEvent(QEvent *e);
Waypoint* wp;
// Special widgets extendending the
// waypoint view to mission capabilities
Ui_QGCCustomWaypointAction* customCommand;
QGC_WAYPOINTVIEW_MODE viewMode;
private:
Ui::WaypointView *m_ui;
......
......@@ -789,13 +789,13 @@ void TimeSeriesData::append(quint64 ms, double value)
this->value[count] = value;
this->lastValue = value;
this->mean = 0;
QList<double> medianList = QList<double>();
//QList<double> medianList = QList<double>();
for (unsigned int i = 0; (i < averageWindow) && (((int)count - (int)i) >= 0); ++i)
{
this->mean += this->value[count-i];
medianList.append(this->value[count-i]);
//medianList.append(this->value[count-i]);
}
mean = mean / static_cast<double>(qMin(averageWindow,static_cast<unsigned int>(count)));
this->mean = mean / static_cast<double>(qMin(averageWindow,static_cast<unsigned int>(count)));
this->variance = 0;
for (unsigned int i = 0; (i < averageWindow) && (((int)count - (int)i) >= 0); ++i)
......@@ -804,19 +804,19 @@ void TimeSeriesData::append(quint64 ms, double value)
}
this->variance = this->variance / static_cast<double>(qMin(averageWindow,static_cast<unsigned int>(count)));
qSort(medianList);
if (medianList.count() > 2)
{
if (medianList.count() % 2 == 0)
{
median = (medianList.at(medianList.count()/2) + medianList.at(medianList.count()/2+1)) / 2.0;
}
else
{
median = medianList.at(medianList.count()/2+1);
}
}
// qSort(medianList);
// if (medianList.count() > 2)
// {
// if (medianList.count() % 2 == 0)
// {
// median = (medianList.at(medianList.count()/2) + medianList.at(medianList.count()/2+1)) / 2.0;
// }
// else
// {
// median = medianList.at(medianList.count()/2+1);
// }
// }
// Update statistical values
if(ms < startTime) startTime = ms;
......
......@@ -107,7 +107,9 @@ updateTimer(new QTimer())
int labelRow = curvesWidgetLayout->rowCount();
curvesWidgetLayout->addWidget(new QLabel(tr("On")), labelRow, 0, 1, 2);
selectAllCheckBox = new QCheckBox("", this);
connect(selectAllCheckBox, SIGNAL(clicked(bool)), this, SLOT(selectAllCurves(bool)));
curvesWidgetLayout->addWidget(selectAllCheckBox, labelRow, 0, 1, 2);
label = new QLabel(this);
label->setText("Name");
......@@ -153,6 +155,15 @@ LinechartWidget::~LinechartWidget()
listedCurves = NULL;
}
void LinechartWidget::selectAllCurves(bool all)
{
QMap<QString, QLabel*>::iterator i;
for (i = curveLabels->begin(); i != curveLabels->end(); ++i)
{
activePlot->setVisible(i.key(), all);
}
}
void LinechartWidget::writeSettings()
{
QSettings settings;
......@@ -299,7 +310,7 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
// Log data
if (logging)
{
if (activePlot->isVisible(curve))
if (activePlot->isVisible(curve+unit))
{
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
......@@ -365,7 +376,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Log data
if (logging)
{
if (activePlot->isVisible(curve))
if (activePlot->isVisible(curve+unit))
{
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
......@@ -416,7 +427,7 @@ void LinechartWidget::refresh()
QMap<QString, QLabel*>::iterator j;
for (j = curveMeans->begin(); j != curveMeans->end(); ++j)
{
double val = activePlot->getCurrentValue(j.key());
double val = activePlot->getMean(j.key());
int intval = static_cast<int>(val);
if (intval >= 100000 || intval <= -100000)
{
......@@ -660,6 +671,7 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
// TODO
// Connect actions
connect(selectAllCheckBox, SIGNAL(clicked(bool)), checkBox, SLOT(setChecked(bool)));
QObject::connect(checkBox, SIGNAL(clicked(bool)), this, SLOT(takeButtonClick(bool)));
QObject::connect(this, SIGNAL(curveVisible(QString, bool)), plot, SLOT(setVisible(QString, bool)));
......
......@@ -99,6 +99,8 @@ public slots:
void writeSettings();
/** @brief Read the current configuration from disk */
void readSettings();
/** @brief Select all curves */
void selectAllCurves(bool all);
protected:
void addCurveToList(QString curve);
......@@ -145,6 +147,7 @@ protected:
quint64 logStartTime;
QTimer* updateTimer;
LogCompressor* compressor;
QCheckBox* selectAllCheckBox;
static const int updateInterval = 400; ///< Time between number updates, in milliseconds
static const int MAX_CURVE_MENUITEM_NUMBER = 8;
......
......@@ -3,6 +3,8 @@
#include <qmath.h>
#include "QGC.h"
MAV2DIcon::MAV2DIcon(UASInterface* uas, int radius, int type, const QColor& color, QString name, Alignment alignment, QPen* pen)
: Point(uas->getLatitude(), uas->getLongitude(), name, alignment),
yaw(0.0f),
......@@ -112,7 +114,10 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
// DRAW AIRPLANE
// Rotate 180 degs more since the icon is oriented downwards
float yawRotate = (yaw/(float)M_PI)*180.0f + 180.0f+180.0f;
//float yawRotate = (yaw/(float)M_PI)*180.0f + 180.0f+180.0f;
const float yawDeg = ((yaw/M_PI)*180.0f)+180.0f+180.0f;
int yawRotate = static_cast<int>(yawDeg) % 360;
painter.rotate(yawRotate);
......@@ -159,7 +164,8 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
{
// QUADROTOR
float iconSize = radius*0.9f;
float yawRotate = (yaw/(float)M_PI)*180.0f + 180.0f;
const float yawDeg = ((yaw/M_PI)*180.0f)+180.0f;
int yawRotate = static_cast<int>(yawDeg) % 360;
painter.rotate(yawRotate);
......@@ -201,8 +207,8 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
{
// DRAW AIRPLANE
float yawRotate = (yaw/(float)M_PI)*180.0f + 180.0f;
const float yawDeg = ((yaw/M_PI)*180.0f)+180.0f;
int yawRotate = static_cast<int>(yawDeg) % 360;
painter.rotate(yawRotate);
//qDebug() << "ICON SIZE:" << radius;
......
......@@ -211,10 +211,10 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
}
}
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
Q_UNUSED(usec);
javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 18).arg(lon, 0, 'f', 18).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);
}
......
......@@ -79,7 +79,7 @@ public slots:
/** @brief Set the currently selected UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Update the global position */
void updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
/** @brief Update a single waypoint */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief Update the waypoint list */
......
......@@ -89,7 +89,9 @@ 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)));
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(showStatusText(int, int, int, QString)));
connect(uas, SIGNAL(navModeChanged(int, int, QString)), this, SLOT(updateNavMode(int, int, QString)));
// Setup UAS selection
connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
......@@ -151,6 +153,22 @@ void UASView::heartbeatTimeout()
timeout = true;
}
void UASView::updateNavMode(int uasid, int mode, const QString& text)
{
Q_UNUSED(uasid);
Q_UNUSED(mode);
m_ui->navLabel->setText(text);
}
void UASView::showStatusText(int uasid, int componentid, int severity, QString text)
{
Q_UNUSED(uasid);
Q_UNUSED(componentid);
Q_UNUSED(severity);
//m_ui->statusTextLabel->setText(text);
stateDesc = text;
}
/**
* Set the background color based on the MAV color. If the MAV is selected as the
* currently actively controlled system, the frame color is highlighted
......@@ -347,7 +365,7 @@ void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, do
void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec)
{
Q_UNUSED(usec);
totalSpeed = sqrt((pow(x, 2) + pow(y, 2) + pow(z, 2)));
totalSpeed = sqrt(x*x + y*y + z*z);
}
void UASView::currentWaypointUpdated(quint16 waypoint)
......@@ -435,7 +453,7 @@ void UASView::setBatterySpecs()
{
bool ok;
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)"), 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,
uas->getBatterySpecs(), &ok);
if (ok && !newName.isEmpty()) uas->setBatterySpecs(newName);
......
......@@ -86,6 +86,10 @@ public slots:
void selectAirframe();
/** @brief Select the battery type */
void setBatterySpecs();
/** @brief Show a status text message */
void showStatusText(int uasid, int componentid, int severity, QString text);
/** @brief Update the navigation mode state */
void updateNavMode(int uasid, int mode, const QString& text);
protected:
void changeEvent(QEvent *e);
......
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