Browse Source

Formatting, fixing audio alarms

QGC4.4
LM 13 years ago
parent
commit
a347a65985
  1. 1
      .gitignore
  2. 0
      files/audio/alert.wav
  3. 15
      qgroundcontrol.pri
  4. 51
      src/GAudioOutput.cc
  5. 48
      src/comm/MAVLinkSimulationLink.cc
  6. 246
      src/uas/UAS.cc
  7. 1
      src/uas/UAS.h
  8. 51
      src/ui/HSIDisplay.cc
  9. 1
      src/ui/HSIDisplay.h

1
.gitignore vendored

@ -22,7 +22,6 @@ debug
release release
qgroundcontrol qgroundcontrol
mavlinkgen-build-desktop mavlinkgen-build-desktop
*.wav
qgroundcontrol.xcodeproj/** qgroundcontrol.xcodeproj/**
doc/html doc/html
doc/doxy.log doc/doxy.log

0
audio/alert.wav → files/audio/alert.wav

15
qgroundcontrol.pri

@ -81,8 +81,6 @@ macx|macx-g++42|macx-g++: {
ICON = $$BASEDIR/images/icons/macx.icns ICON = $$BASEDIR/images/icons/macx.icns
# Copy audio files if needed
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy contributed files # Copy contributed files
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/qgroundcontrol.app/Contents/MacOS QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy google earth starter file # Copy google earth starter file
@ -274,7 +272,6 @@ message("Compiling for linux 32")
} }
# Validated copy commands # Validated copy commands
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR
@ -367,7 +364,6 @@ linux-g++-64 {
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/debug QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/debug
} }
DESTDIR = $$TARGETDIR/debug DESTDIR = $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/debug QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/debug QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/debug
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/debug/images QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/debug/images
@ -378,7 +374,6 @@ linux-g++-64 {
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/release QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/release
} }
DESTDIR = $$TARGETDIR/release DESTDIR = $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/release QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/release QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/release
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/release/images QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/release/images
@ -455,7 +450,6 @@ DEFINES += QGC_OSG_ENABLED
exists($$TARGETDIR/debug) { exists($$TARGETDIR/debug) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\debug\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\debug\\files" /E /I $$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\debug\\files" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\debug\\models" /E /I $$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\debug\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
@ -476,7 +470,6 @@ DEFINES += QGC_OSG_ENABLED
exists($$TARGETDIR/release) { exists($$TARGETDIR/release) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\release\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\release\\files" /E /I $$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\release\\files" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\release\\models" /E /I $$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\release\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\release\\earth.html" $$escape_expand(\\n)) QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\release\\earth.html" $$escape_expand(\\n))
@ -543,13 +536,13 @@ win32-g++ {
message("Using cp to copy image and audio files to executable") message("Using cp to copy image and audio files to executable")
debug { debug {
QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/debug/SDL.dll QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/debug/SDL.dll
QMAKE_POST_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/debug/audio QMAKE_POST_LINK += && cp -r $$BASEDIR/files $$TARGETDIR/debug/files
QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/debug/models QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/debug/models
} }
release { release {
QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/release/SDL.dll QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/release/SDL.dll
QMAKE_POST_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/release/audio QMAKE_POST_LINK += && cp -r $$BASEDIR/files $$TARGETDIR/release/files
QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/release/models QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/release/models
} }
@ -561,14 +554,14 @@ win32-g++ {
exists($$TARGETDIR/debug) { exists($$TARGETDIR/debug) {
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\debug\\SDL.dll\" QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\debug\\SDL.dll\"
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\audio\" \"$$TARGETDIR_WIN\\debug\\audio\\\" /S /E /Y QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\files\" \"$$TARGETDIR_WIN\\debug\\files\\\" /S /E /Y
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\models\" \"$$TARGETDIR_WIN\\debug\\models\\\" /S /E /Y QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\models\" \"$$TARGETDIR_WIN\\debug\\models\\\" /S /E /Y
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\images\\earth.html\" \"$$TARGETDIR_WIN\\debug\\earth.html\" QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\images\\earth.html\" \"$$TARGETDIR_WIN\\debug\\earth.html\"
} }
exists($$TARGETDIR/release) { exists($$TARGETDIR/release) {
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\release\\SDL.dll\" QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\release\\SDL.dll\"
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\audio\" \"$$TARGETDIR_WIN\\release\\audio\\\" /S /E /Y QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\files\" \"$$TARGETDIR_WIN\\release\\files\\\" /S /E /Y
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\models\" \"$$TARGETDIR_WIN\\release\\models\\\" /S /E /Y QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\models\" \"$$TARGETDIR_WIN\\release\\models\\\" /S /E /Y
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\images\\earth.html\" \"$$TARGETDIR_WIN\\release\\earth.html\" QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\images\\earth.html\" \"$$TARGETDIR_WIN\\release\\earth.html\"
} }

51
src/GAudioOutput.cc

@ -77,7 +77,8 @@ extern "C" {
GAudioOutput* GAudioOutput::instance() GAudioOutput* GAudioOutput::instance()
{ {
static GAudioOutput* _instance = 0; static GAudioOutput* _instance = 0;
if(_instance == 0) { if(_instance == 0)
{
_instance = new GAudioOutput(); _instance = new GAudioOutput();
// Set the application as parent to ensure that this object // Set the application as parent to ensure that this object
// will be destroyed when the main application exits // will be destroyed when the main application exits
@ -106,12 +107,16 @@ GAudioOutput::GAudioOutput(QObject* parent) : QObject(parent),
#if _MSC_VER2 #if _MSC_VER2
ISpVoice * pVoice = NULL; ISpVoice * pVoice = NULL;
if (FAILED(::CoInitialize(NULL))) { if (FAILED(::CoInitialize(NULL)))
{
qDebug("Creating COM object for audio output failed!"); qDebug("Creating COM object for audio output failed!");
} else { }
else
{
HRESULT hr = CoCreateInstance(CLSID_SpVoice, NULL, CLSCTX_ALL, IID_ISpVoice, (void **)&pVoice;); HRESULT hr = CoCreateInstance(CLSID_SpVoice, NULL, CLSCTX_ALL, IID_ISpVoice, (void **)&pVoice;);
if( SUCCEEDED( hr ) ) { if( SUCCEEDED( hr ) )
{
hr = pVoice->Speak(L"Hello world", 0, NULL); hr = pVoice->Speak(L"Hello world", 0, NULL);
pVoice->Release(); pVoice->Release();
pVoice = NULL; pVoice = NULL;
@ -146,7 +151,8 @@ GAudioOutput::GAudioOutput(QObject* parent) : QObject(parent),
void GAudioOutput::mute(bool mute) void GAudioOutput::mute(bool mute)
{ {
if (mute != muted) { if (mute != muted)
{
this->muted = mute; this->muted = mute;
QSettings settings; QSettings settings;
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", this->muted); settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", this->muted);
@ -162,11 +168,13 @@ bool GAudioOutput::isMuted()
bool GAudioOutput::say(QString text, int severity) bool GAudioOutput::say(QString text, int severity)
{ {
if (!muted) { if (!muted)
{
// TODO Add severity filter // TODO Add severity filter
Q_UNUSED(severity); Q_UNUSED(severity);
bool res = false; bool res = false;
if (!emergency) { if (!emergency)
{
// Speech synthesis is only supported with MSVC compiler // Speech synthesis is only supported with MSVC compiler
#ifdef _MSC_VER2 #ifdef _MSC_VER2
@ -202,7 +210,9 @@ bool GAudioOutput::say(QString text, int severity)
#endif #endif
} }
return res; return res;
} else { }
else
{
return false; return false;
} }
} }
@ -212,22 +222,26 @@ bool GAudioOutput::say(QString text, int severity)
*/ */
bool GAudioOutput::alert(QString text) bool GAudioOutput::alert(QString text)
{ {
if (!emergency || !muted) { if (!emergency || !muted)
{
// Play alert sound // Play alert sound
beep(); beep();
// Say alert message // Say alert message
say(text, 2); say(text, 2);
return true; return true;
} else { }
else
{
return false; return false;
} }
} }
void GAudioOutput::notifyPositive() void GAudioOutput::notifyPositive()
{ {
if (!muted) { if (!muted)
{
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/double_notify.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/files/audio/double_notify.wav"));
//m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
//m_media->play(); //m_media->play();
} }
@ -235,9 +249,10 @@ void GAudioOutput::notifyPositive()
void GAudioOutput::notifyNegative() void GAudioOutput::notifyNegative()
{ {
if (!muted) { if (!muted)
{
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/flat_notify.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/files/audio/flat_notify.wav"));
//m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
//m_media->play(); //m_media->play();
} }
@ -252,7 +267,8 @@ void GAudioOutput::notifyNegative()
*/ */
bool GAudioOutput::startEmergency() bool GAudioOutput::startEmergency()
{ {
if (!emergency) { if (!emergency)
{
emergency = true; emergency = true;
// Beep immediately and then start timer // Beep immediately and then start timer
if (!muted) beep(); if (!muted) beep();
@ -279,9 +295,10 @@ bool GAudioOutput::stopEmergency()
void GAudioOutput::beep() void GAudioOutput::beep()
{ {
if (!muted) { if (!muted)
{
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/alert.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/files/audio/alert.wav"));
qDebug() << "FILE:" << f.fileName(); qDebug() << "FILE:" << f.fileName();
//m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
//m_media->play(); //m_media->play();

48
src/comm/MAVLinkSimulationLink.cc

@ -678,8 +678,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
int bufferlength = 0; int bufferlength = 0;
// Output all bytes as hex digits // Output all bytes as hex digits
int i; for (int i=0; i<size; i++)
for (i=0; i<size; i++)
{ {
if (mavlink_parse_char(this->id, data[i], &msg, &comm)) if (mavlink_parse_char(this->id, data[i], &msg, &comm))
{ {
@ -687,16 +686,19 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
qDebug() << "SIMULATION LINK RECEIVED MESSAGE!"; qDebug() << "SIMULATION LINK RECEIVED MESSAGE!";
emit messageReceived(msg); emit messageReceived(msg);
switch (msg.msgid) { switch (msg.msgid)
{
// SET THE SYSTEM MODE // SET THE SYSTEM MODE
case MAVLINK_MSG_ID_SET_MODE: { case MAVLINK_MSG_ID_SET_MODE:
{
mavlink_set_mode_t mode; mavlink_set_mode_t mode;
mavlink_msg_set_mode_decode(&msg, &mode); mavlink_msg_set_mode_decode(&msg, &mode);
// Set mode indepent of mode.target // Set mode indepent of mode.target
system.base_mode = mode.base_mode; system.base_mode = mode.base_mode;
} }
break; break;
case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT: { case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
{
mavlink_set_local_position_setpoint_t set; mavlink_set_local_position_setpoint_t set;
mavlink_msg_set_local_position_setpoint_decode(&msg, &set); mavlink_msg_set_local_position_setpoint_decode(&msg, &set);
spX = set.x; spX = set.x;
@ -714,7 +716,8 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
break; break;
// EXECUTE OPERATOR ACTIONS // EXECUTE OPERATOR ACTIONS
case MAVLINK_MSG_ID_COMMAND_LONG: { case MAVLINK_MSG_ID_COMMAND_LONG:
{
mavlink_command_long_t action; mavlink_command_long_t action;
mavlink_msg_command_long_decode(&msg, &action); mavlink_msg_command_long_decode(&msg, &action);
@ -756,12 +759,13 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
break; break;
#endif #endif
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION"; qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
mavlink_param_request_list_t read; mavlink_param_request_list_t read;
mavlink_msg_param_request_list_decode(&msg, &read); mavlink_msg_param_request_list_decode(&msg, &read);
// if (read.target_system == systemId) if (read.target_system == systemId)
// { {
// Output all params // Output all params
// Iterate through all components, through all parameters and emit them // Iterate through all components, through all parameters and emit them
QMap<QString, float>::iterator i; QMap<QString, float>::iterator i;
@ -781,19 +785,22 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
qDebug() << "SIMULATION SENT PARAMETERS TO GCS"; qDebug() << "SIMULATION SENT PARAMETERS TO GCS";
// } }
} }
break; break;
case MAVLINK_MSG_ID_PARAM_SET: { case MAVLINK_MSG_ID_PARAM_SET:
{
// Drop on even milliseconds // Drop on even milliseconds
if (QGC::groundTimeMilliseconds() % 2 == 0) { if (QGC::groundTimeMilliseconds() % 2 == 0)
{
qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER"; qDebug() << "SIMULATION RECEIVED COMMAND TO SET PARAMETER";
mavlink_param_set_t set; mavlink_param_set_t set;
mavlink_msg_param_set_decode(&msg, &set); mavlink_msg_param_set_decode(&msg, &set);
// if (set.target_system == systemId) // if (set.target_system == systemId)
// { // {
QString key = QString((char*)set.param_id); QString key = QString((char*)set.param_id);
if (onboardParams.contains(key)) { if (onboardParams.contains(key))
{
onboardParams.remove(key); onboardParams.remove(key);
onboardParams.insert(key, set.param_value); onboardParams.insert(key, set.param_value);
@ -809,13 +816,15 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
} }
break; break;
case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
{
qDebug() << "SIMULATION RECEIVED COMMAND TO SEND PARAMETER"; qDebug() << "SIMULATION RECEIVED COMMAND TO SEND PARAMETER";
mavlink_param_request_read_t read; mavlink_param_request_read_t read;
mavlink_msg_param_request_read_decode(&msg, &read); mavlink_msg_param_request_read_decode(&msg, &read);
QByteArray bytes((char*)read.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN); QByteArray bytes((char*)read.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
QString key = QString(bytes); QString key = QString(bytes);
if (onboardParams.contains(key)) { if (onboardParams.contains(key))
{
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
@ -826,7 +835,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
streampointer+=bufferlength; streampointer+=bufferlength;
//qDebug() << "Sending PARAM" << key; //qDebug() << "Sending PARAM" << key;
} else if (read.param_index < onboardParams.size()) { }
else if (read.param_index < onboardParams.size())
{
key = onboardParams.keys().at(read.param_index); key = onboardParams.keys().at(read.param_index);
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
@ -842,8 +853,6 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
break; break;
} }
} }
unsigned char v=data[i]; unsigned char v=data[i];
fprintf(stderr,"%02x ", v); fprintf(stderr,"%02x ", v);
@ -851,7 +860,8 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
fprintf(stderr,"\n"); fprintf(stderr,"\n");
readyBufferMutex.lock(); readyBufferMutex.lock();
for (int i = 0; i < streampointer; i++) { for (int i = 0; i < streampointer; i++)
{
readyBuffer.enqueue(*(stream + i)); readyBuffer.enqueue(*(stream + i));
} }
readyBufferMutex.unlock(); readyBufferMutex.unlock();

246
src/uas/UAS.cc

@ -75,12 +75,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
pitch(0.0), pitch(0.0),
yaw(0.0), yaw(0.0),
statusTimeout(new QTimer(this)), statusTimeout(new QTimer(this)),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedPointCloudTimestamp(0.0), receivedPointCloudTimestamp(0.0),
receivedRGBDImageTimestamp(0.0), receivedRGBDImageTimestamp(0.0),
receivedObstacleListTimestamp(0.0), receivedObstacleListTimestamp(0.0),
receivedPathTimestamp(0.0), receivedPathTimestamp(0.0),
#endif #endif
paramsOnceRequested(false), paramsOnceRequested(false),
airframe(QGC_AIRFRAME_EASYSTAR), airframe(QGC_AIRFRAME_EASYSTAR),
attitudeKnown(false), attitudeKnown(false),
@ -274,6 +274,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{ {
case MAVLINK_MSG_ID_HEARTBEAT: case MAVLINK_MSG_ID_HEARTBEAT:
{ {
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
lastHeartbeat = QGC::groundTimeUsecs(); lastHeartbeat = QGC::groundTimeUsecs();
emit heartbeat(this); emit heartbeat(this);
mavlink_heartbeat_t state; mavlink_heartbeat_t state;
@ -381,22 +385,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
GAudioOutput::instance()->say(audiostring.toLower()); GAudioOutput::instance()->say(audiostring.toLower());
} }
// if (state.system_status == MAV_STATE_POWEROFF) // if (state.system_status == MAV_STATE_POWEROFF)
// { // {
// emit systemRemoved(this); // emit systemRemoved(this);
// emit systemRemoved(); // emit systemRemoved();
// } // }
} }
break; break;
// case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: // case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
// case MAVLINK_MSG_ID_NAMED_VALUE_INT: // case MAVLINK_MSG_ID_NAMED_VALUE_INT:
// // Receive named value message // // Receive named value message
// receiveMessageNamedValue(message); // receiveMessageNamedValue(message);
// break; // break;
case MAVLINK_MSG_ID_SYS_STATUS: case MAVLINK_MSG_ID_SYS_STATUS:
{ {
if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2) if (multiComponentSourceDetected && wrongComponent)
{ {
break; break;
} }
@ -445,22 +449,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
pitch = QGC::limitAngleToPMPIf(attitude.pitch); pitch = QGC::limitAngleToPMPIf(attitude.pitch);
yaw = QGC::limitAngleToPMPIf(attitude.yaw); yaw = QGC::limitAngleToPMPIf(attitude.yaw);
// // Emit in angles // // Emit in angles
// // Convert yaw angle to compass value // // Convert yaw angle to compass value
// // in 0 - 360 deg range // // in 0 - 360 deg range
// float compass = (yaw/M_PI)*180.0+360.0f; // float compass = (yaw/M_PI)*180.0+360.0f;
// if (compass > -10000 && compass < 10000) // if (compass > -10000 && compass < 10000)
// { // {
// while (compass > 360.0f) { // while (compass > 360.0f) {
// compass -= 360.0f; // compass -= 360.0f;
// } // }
// } // }
// else // else
// { // {
// // Set to 0, since it is an invalid value // // Set to 0, since it is an invalid value
// compass = 0.0f; // compass = 0.0f;
// } // }
attitudeKnown = true; attitudeKnown = true;
emit attitudeChanged(this, roll, pitch, yaw, time); emit attitudeChanged(this, roll, pitch, yaw, time);
@ -890,63 +894,63 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
#endif #endif
// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT: // case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
// { // {
// mavlink_object_detection_event_t event; // mavlink_object_detection_event_t event;
// mavlink_msg_object_detection_event_decode(&message, &event); // mavlink_msg_object_detection_event_decode(&message, &event);
// QString str(event.name); // QString str(event.name);
// emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance); // emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
// } // }
// break; // break;
// WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
// case MAVLINK_MSG_ID_MEMORY_VECT: // case MAVLINK_MSG_ID_MEMORY_VECT:
// { // {
// mavlink_memory_vect_t vect; // mavlink_memory_vect_t vect;
// mavlink_msg_memory_vect_decode(&message, &vect); // mavlink_msg_memory_vect_decode(&message, &vect);
// QString str("mem_%1"); // QString str("mem_%1");
// quint64 time = getUnixTime(0); // quint64 time = getUnixTime(0);
// int16_t *mem0 = (int16_t *)&vect.value[0]; // int16_t *mem0 = (int16_t *)&vect.value[0];
// uint16_t *mem1 = (uint16_t *)&vect.value[0]; // uint16_t *mem1 = (uint16_t *)&vect.value[0];
// int32_t *mem2 = (int32_t *)&vect.value[0]; // int32_t *mem2 = (int32_t *)&vect.value[0];
// // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem // // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
// float *mem4 = (float *)&vect.value[0]; // float *mem4 = (float *)&vect.value[0];
// if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ; // if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
// if ( vect.ver == 1) // if ( vect.ver == 1)
// { // {
// switch (vect.type) { // switch (vect.type) {
// default: // default:
// case 0: // case 0:
// for (int i = 0; i < 16; i++) // for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
// break; // break;
// case 1: // case 1:
// for (int i = 0; i < 16; i++) // for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
// break; // break;
// case 2: // case 2:
// for (int i = 0; i < 16; i++) // for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
// break; // break;
// case 3: // case 3:
// for (int i = 0; i < 16; i++) // for (int i = 0; i < 16; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
// break; // break;
// case 4: // case 4:
// for (int i = 0; i < 8; i++) // for (int i = 0; i < 8; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
// break; // break;
// case 5: // case 5:
// for (int i = 0; i < 8; i++) // for (int i = 0; i < 8; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
// break; // break;
// case 6: // case 6:
// for (int i = 0; i < 8; i++) // for (int i = 0; i < 8; i++)
// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time); // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
// break; // break;
// } // }
// } // }
// } // }
// break; // break;
#ifdef MAVLINK_ENABLED_UALBERTA #ifdef MAVLINK_ENABLED_UALBERTA
case MAVLINK_MSG_ID_NAV_FILTER_BIAS: case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
{ {
@ -1127,10 +1131,6 @@ void UAS::setHomePosition(double lat, double lon, double alt)
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt);
// Send message twice to increase chance that it reaches its goal // Send message twice to increase chance that it reaches its goal
sendMessage(msg); sendMessage(msg);
// Wait 15 ms
QGC::SLEEP::usleep(15000);
// Send again
sendMessage(msg);
// Send new home position to UAS // Send new home position to UAS
mavlink_set_gps_global_origin_t home; mavlink_set_gps_global_origin_t home;
@ -1164,10 +1164,6 @@ void UAS::setLocalOriginAtCurrentGPSPosition()
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0);
// Send message twice to increase chance that it reaches its goal // Send message twice to increase chance that it reaches its goal
sendMessage(msg); sendMessage(msg);
// Wait 15 ms
QGC::SLEEP::usleep(15000);
// Send again
sendMessage(msg);
} }
} }
@ -1614,7 +1610,7 @@ quint64 UAS::getUptime() const
} }
else else
{ {
return MG::TIME::getGroundTimeNow() - startTime; return QGC::groundTimeMilliseconds() - startTime;
} }
} }
@ -1626,7 +1622,7 @@ int UAS::getCommunicationStatus() const
void UAS::requestParameters() void UAS::requestParameters()
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25); mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
sendMessage(msg); sendMessage(msg);
} }
@ -2088,7 +2084,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
sendMessage(message); sendMessage(message);
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow()); emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
} }
else else
{ {
@ -2168,30 +2164,30 @@ bool UAS::emergencyKILL()
{ {
halt(); halt();
// FIXME MAVLINKV10PORTINGNEEDED // FIXME MAVLINKV10PORTINGNEEDED
// bool result = false; // bool result = false;
// QMessageBox msgBox; // QMessageBox msgBox;
// msgBox.setIcon(QMessageBox::Critical); // msgBox.setIcon(QMessageBox::Critical);
// msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS"); // msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
// msgBox.setInformativeText("Do you want to cut power on all systems?"); // msgBox.setInformativeText("Do you want to cut power on all systems?");
// msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); // msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
// msgBox.setDefaultButton(QMessageBox::Cancel); // msgBox.setDefaultButton(QMessageBox::Cancel);
// int ret = msgBox.exec(); // int ret = msgBox.exec();
// // Close the message box shortly after the click to prevent accidental clicks // // Close the message box shortly after the click to prevent accidental clicks
// QTimer::singleShot(5000, &msgBox, SLOT(reject())); // QTimer::singleShot(5000, &msgBox, SLOT(reject()));
// if (ret == QMessageBox::Yes) // if (ret == QMessageBox::Yes)
// { // {
// mavlink_message_t msg; // mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI // // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL); // mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL);
// // Send message twice to increase chance of reception // // Send message twice to increase chance of reception
// sendMessage(msg); // sendMessage(msg);
// sendMessage(msg); // sendMessage(msg);
// result = true; // result = true;
// } // }
// return result; // return result;
return false; return false;
} }
@ -2322,19 +2318,19 @@ QString UAS::getShortModeTextFor(int id)
} }
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
{ {
mode += "GUIDED"; mode += "|GUID";
} }
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
{ {
mode += "STABILIZED"; mode += "|STAB";
} }
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
{ {
mode += "TEST"; mode += "|TEST";
} }
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
{ {
mode += "MANUAL"; mode += "|MAN";
} }
if (modeid == 0) if (modeid == 0)
@ -2345,11 +2341,11 @@ QString UAS::getShortModeTextFor(int id)
// ARMED STATE DECODING // ARMED STATE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{ {
mode.prepend("A|"); mode.prepend("A/");
} }
else else
{ {
mode.prepend("D|"); mode.prepend("D/");
} }
// HARDWARE IN THE LOOP DECODING // HARDWARE IN THE LOOP DECODING
@ -2480,7 +2476,7 @@ QString UAS::getBatterySpecs()
int UAS::calculateTimeRemaining() int UAS::calculateTimeRemaining()
{ {
quint64 dt = MG::TIME::getGroundTimeNow() - startTime; quint64 dt = QGC::groundTimeMilliseconds() - startTime;
double seconds = dt / 1000.0f; double seconds = dt / 1000.0f;
double voltDifference = startVoltage - currentVoltage; double voltDifference = startVoltage - currentVoltage;
if (voltDifference <= 0) voltDifference = 0.00000000001f; if (voltDifference <= 0) voltDifference = 0.00000000001f;

1
src/uas/UAS.h

@ -219,6 +219,7 @@ protected: //COMMENTS FOR TEST UNIT
float chargeLevel; ///< Charge level of battery, in percent float chargeLevel; ///< Charge level of battery, in percent
int timeRemaining; ///< Remaining time calculated based on previous and current int timeRemaining; ///< Remaining time calculated based on previous and current
uint8_t mode; ///< The current mode of the MAV uint8_t mode; ///< The current mode of the MAV
uint32_t custom_mode; ///< The current mode of the MAV
int status; ///< The current status of the MAV int status; ///< The current status of the MAV
uint32_t navMode; ///< The current navigation mode of the MAV uint32_t navMode; ///< The current navigation mode of the MAV
quint64 onboardTimeOffset; quint64 onboardTimeOffset;

51
src/ui/HSIDisplay.cc

@ -104,6 +104,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
leftDragStarted(false), leftDragStarted(false),
mouseHasMoved(false), mouseHasMoved(false),
actionPending(false), actionPending(false),
directSending(false),
userSetPointSet(false), userSetPointSet(false),
userXYSetPointSet(false) userXYSetPointSet(false)
{ {
@ -637,37 +638,53 @@ void HSIDisplay::keyPressEvent(QKeyEvent* event)
statusClearTimer.start(); statusClearTimer.start();
sendBodySetPointCoordinates(); sendBodySetPointCoordinates();
} }
else if ((event->key() == Qt::Key_Up)) else if ((event->key() == Qt::Key_W))
{ {
setBodySetpointCoordinateXY(0.5, 0); setBodySetpointCoordinateXY(1.0, 0);
setBodySetpointCoordinateZ(uas->getLocalZ());
setBodySetpointCoordinateYaw(uas->getYaw());
} }
else if ((event->key() == Qt::Key_Down)) else if ((event->key() == Qt::Key_S))
{ {
setBodySetpointCoordinateXY(-0.5, 0); setBodySetpointCoordinateXY(-1.0, 0);
setBodySetpointCoordinateZ(uas->getLocalZ());
setBodySetpointCoordinateYaw(uas->getYaw());
} }
else if ((event->key() == Qt::Key_Left)) else if ((event->key() == Qt::Key_A))
{ {
setBodySetpointCoordinateXY(0, -0.5); setBodySetpointCoordinateXY(0, -1.0);
setBodySetpointCoordinateZ(uas->getLocalZ());
setBodySetpointCoordinateYaw(uas->getYaw());
} }
else if ((event->key() == Qt::Key_Right)) else if ((event->key() == Qt::Key_D))
{ {
setBodySetpointCoordinateXY(0, 0.5); setBodySetpointCoordinateXY(0, 1.0);
setBodySetpointCoordinateZ(uas->getLocalZ());
setBodySetpointCoordinateYaw(uas->getYaw());
} }
else if ((event->key() == Qt::Key_Plus)) else if ((event->key() == Qt::Key_Up))
{ {
setBodySetpointCoordinateZ(-0.2); setBodySetpointCoordinateXY(0, 0);
setBodySetpointCoordinateZ(-0.5+uas->getLocalZ());
setBodySetpointCoordinateYaw(uas->getYaw());
} }
else if ((event->key() == Qt::Key_Minus)) else if ((event->key() == Qt::Key_Down))
{ {
setBodySetpointCoordinateZ(+0.2); setBodySetpointCoordinateZ(+0.5+uas->getLocalZ());
setBodySetpointCoordinateXY(0, 0);
setBodySetpointCoordinateYaw(uas->getYaw());
} }
else if ((event->key() == Qt::Key_L)) else if ((event->key() == Qt::Key_Left))
{ {
setBodySetpointCoordinateYaw(-0.1); setBodySetpointCoordinateXY(0, 0);
setBodySetpointCoordinateZ(uas->getLocalZ());
setBodySetpointCoordinateYaw(-0.2+uas->getYaw());
} }
else if ((event->key() == Qt::Key_R)) else if ((event->key() == Qt::Key_Right))
{ {
setBodySetpointCoordinateYaw(0.1); setBodySetpointCoordinateXY(0, 0);
setBodySetpointCoordinateZ(uas->getLocalZ());
setBodySetpointCoordinateYaw(0.2+uas->getYaw());
} }
HDDisplay::keyPressEvent(event); HDDisplay::keyPressEvent(event);
} }
@ -811,7 +828,7 @@ void HSIDisplay::sendBodySetPointCoordinates()
double dx = uiXSetCoordinate - uas->getLocalX(); double dx = uiXSetCoordinate - uas->getLocalX();
double dy = uiYSetCoordinate - uas->getLocalY(); double dy = uiYSetCoordinate - uas->getLocalY();
double dz = uiZSetCoordinate - uas->getLocalZ(); double dz = uiZSetCoordinate - uas->getLocalZ();
bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 1.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate); bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 3.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
if (valid) if (valid)
{ {
uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet); uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);

1
src/ui/HSIDisplay.h

@ -175,6 +175,7 @@ protected:
QTimer statusClearTimer; QTimer statusClearTimer;
QString statusMessage; QString statusMessage;
bool actionPending; bool actionPending;
bool directSending;
/** /**
* @brief Private data container class to be used within the HSI widget * @brief Private data container class to be used within the HSI widget

Loading…
Cancel
Save