Commit dd587ce2 authored by dogmaphobic's avatar dogmaphobic

Text to Speech Work

parent c2a3cd0b
......@@ -11,8 +11,8 @@ WindowsBuild {
# the selected autopilot system.
#
# If the user config file exists, it will be included. If this file
# specifies the MAVLINK_CONF variable with a MAVLink dialect, support
# for it will be compiled in to QGC. It will also create a
# specifies the MAVLINK_CONF variable with a MAVLink dialect, support
# for it will be compiled in to QGC. It will also create a
# QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use within the actual code.
#
MAVLINKPATH_REL = libs/mavlink/include/mavlink/v1.0
......@@ -79,20 +79,20 @@ INCLUDEPATH += libs/qwt
# Uninstalling from Linux can be done with `sudo make uninstall`.
#
XBEE_DEPENDENT_HEADERS += \
src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h
src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h
XBEE_DEPENDENT_SOURCES += \
src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp
src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp
XBEE_DEFINES = QGC_XBEE_ENABLED
contains(DEFINES, DISABLE_XBEE) {
message("Skipping support for native XBee API (manual override from command line)")
DEFINES -= DISABLE_XBEE
message("Skipping support for native XBee API (manual override from command line)")
DEFINES -= DISABLE_XBEE
# Otherwise the user can still disable this feature in the user_config.pri file.
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_XBEE) {
message("Skipping support for native XBee API (manual override from user_config.pri)")
......@@ -100,50 +100,50 @@ contains(DEFINES, DISABLE_XBEE) {
linux-g++-64 {
message("Skipping support for XBee API (64-bit Linux builds not supported)")
} else:exists(/usr/include/xbee.h) {
message("Including support for XBee API")
message("Including support for XBee API")
HEADERS += $$XBEE_DEPENDENT_HEADERS
SOURCES += $$XBEE_DEPENDENT_SOURCES
DEFINES += $$XBEE_DEFINES
LIBS += -L/usr/lib -lxbee
} else {
warning("Skipping support for XBee API (missing libraries, see README)")
}
HEADERS += $$XBEE_DEPENDENT_HEADERS
SOURCES += $$XBEE_DEPENDENT_SOURCES
DEFINES += $$XBEE_DEFINES
LIBS += -L/usr/lib -lxbee
} else {
warning("Skipping support for XBee API (missing libraries, see README)")
}
} else:WindowsBuild {
message("Including support for XBee API")
HEADERS += $$XBEE_DEPENDENT_HEADERS
SOURCES += $$XBEE_DEPENDENT_SOURCES
DEFINES += $$XBEE_DEFINES
INCLUDEPATH += libs/thirdParty/libxbee
message("Including support for XBee API")
HEADERS += $$XBEE_DEPENDENT_HEADERS
SOURCES += $$XBEE_DEPENDENT_SOURCES
DEFINES += $$XBEE_DEFINES
INCLUDEPATH += libs/thirdParty/libxbee
LIBS += -l$$BASEDIR/libs/thirdParty/libxbee/lib/libxbee
} else {
message("Skipping support for XBee API (unsupported platform)")
message("Skipping support for XBee API (unsupported platform)")
}
#
# [OPTIONAL] Magellan 3DxWare library. Provides support for 3DConnexion's 3D mice.
#
contains(DEFINES, DISABLE_3DMOUSE) {
message("Skipping support for 3DConnexion mice (manual override from command line)")
DEFINES -= DISABLE_3DMOUSE
message("Skipping support for 3DConnexion mice (manual override from command line)")
DEFINES -= DISABLE_3DMOUSE
# Otherwise the user can still disable this feature in the user_config.pri file.
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_3DMOUSE) {
message("Skipping support for 3DConnexion mice (manual override from user_config.pri)")
} else:LinuxBuild {
exists(/usr/local/lib/libxdrvlib.so) {
message("Including support for 3DConnexion mice")
exists(/usr/local/lib/libxdrvlib.so) {
message("Including support for 3DConnexion mice")
DEFINES += \
QGC_MOUSE_ENABLED_LINUX \
QGC_MOUSE_ENABLED_LINUX \
ParameterCheck
# Hack: Has to be defined for magellan usage
HEADERS += src/input/Mouse6dofInput.h
SOURCES += src/input/Mouse6dofInput.cpp
LIBS += -L/usr/local/lib/ -lxdrvlib
} else {
warning("Skipping support for 3DConnexion mice (missing libraries, see README)")
}
HEADERS += src/input/Mouse6dofInput.h
SOURCES += src/input/Mouse6dofInput.cpp
LIBS += -L/usr/local/lib/ -lxdrvlib
} else {
warning("Skipping support for 3DConnexion mice (missing libraries, see README)")
}
} else:WindowsBuild {
message("Including support for 3DConnexion mice")
......@@ -162,52 +162,52 @@ contains(DEFINES, DISABLE_3DMOUSE) {
libs/thirdParty/3DMouse/win/Mouse3DInput.cpp \
src/input/Mouse6dofInput.cpp
} else {
message("Skipping support for 3DConnexion mice (unsupported platform)")
message("Skipping support for 3DConnexion mice (unsupported platform)")
}
#
# [OPTIONAL] Opal RT-LAB Library. Provides integration with Opal-RT's RT-LAB simulator.
#
contains(DEFINES, DISABLE_RTLAB) {
message("Skipping support for RT-LAB (manual override from command line)")
DEFINES -= DISABLE_RTLAB
message("Skipping support for RT-LAB (manual override from command line)")
DEFINES -= DISABLE_RTLAB
# Otherwise the user can still disable this feature in the user_config.pri file.
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_RTLAB) {
message("Skipping support for RT-LAB (manual override from user_config.pri)")
} else:WindowsBuild {
exists(src/lib/opalrt/OpalApi.h) : exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Including support for RT-LAB")
exists(src/lib/opalrt/OpalApi.h) : exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Including support for RT-LAB")
DEFINES += QGC_RTLAB_ENABLED
DEFINES += QGC_RTLAB_ENABLED
INCLUDEPATH +=
src/lib/opalrt
libs/lib/opal/include \
INCLUDEPATH +=
src/lib/opalrt
libs/lib/opal/include \
FORMS += src/ui/OpalLinkSettings.ui
FORMS += src/ui/OpalLinkSettings.ui
HEADERS += \
src/comm/OpalRT.h \
src/comm/OpalLink.h \
src/comm/Parameter.h \
src/comm/QGCParamID.h \
src/comm/ParameterList.h \
src/ui/OpalLinkConfigurationWindow.h
HEADERS += \
src/comm/OpalRT.h \
src/comm/OpalLink.h \
src/comm/Parameter.h \
src/comm/QGCParamID.h \
src/comm/ParameterList.h \
src/ui/OpalLinkConfigurationWindow.h
SOURCES += \
src/comm/OpalRT.cc \
src/comm/OpalLink.cc \
src/comm/Parameter.cc \
src/comm/QGCParamID.cc \
src/comm/ParameterList.cc \
src/ui/OpalLinkConfigurationWindow.cc
SOURCES += \
src/comm/OpalRT.cc \
src/comm/OpalLink.cc \
src/comm/Parameter.cc \
src/comm/QGCParamID.cc \
src/comm/ParameterList.cc \
src/ui/OpalLinkConfigurationWindow.cc
LIBS += \
-LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi
} else {
warning("Skipping support for RT-LAB (missing libraries, see README)")
}
LIBS += \
-LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi
} else {
warning("Skipping support for RT-LAB (missing libraries, see README)")
}
} else {
message("Skipping support for RT-LAB (unsupported platform)")
}
......@@ -225,12 +225,12 @@ MacBuild {
-F$$BASEDIR/libs/lib/Frameworks \
-framework SDL
} else:LinuxBuild {
PKGCONFIG = sdl
PKGCONFIG = sdl
} else:WindowsBuild {
INCLUDEPATH += \
INCLUDEPATH += \
$$BASEDIR/libs/lib/sdl/msvc/include \
LIBS += \
LIBS += \
-L$$BASEDIR/libs/lib/sdl/msvc/lib \
-lSDLmain \
-lSDL
......@@ -244,20 +244,20 @@ MacBuild {
# Windows is supported as of Windows 7
#
contains (DEFINES, DISABLE_SPEECH) {
message("Skipping support for speech output (manual override from command line)")
DEFINES -= DISABLE_SPEECH
message("Skipping support for speech output (manual override from command line)")
DEFINES -= DISABLE_SPEECH
# Otherwise the user can still disable this feature in the user_config.pri file.
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_SPEECH) {
message("Skipping support for speech output (manual override from user_config.pri)")
} else:LinuxBuild {
exists(/usr/include/espeak) | exists(/usr/local/include/espeak) {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
LIBS += \
-lespeak
} else {
warning("Skipping support for speech output (missing libraries, see README)")
}
exists(/usr/include/espeak) | exists(/usr/local/include/espeak) {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
LIBS += \
-lespeak
} else {
warning("Skipping support for speech output (missing libraries, see README)")
}
}
# Mac support is built into OS 10.6+.
else:MacBuild {
......@@ -270,6 +270,11 @@ else:WindowsBuild {
DEFINES += QGC_SPEECH_ENABLED
LIBS += -lOle32
}
# Android supports speech through native (Java) API.
else:AndroidBuild {
message("Including support for speech output")
DEFINES += QGC_SPEECH_ENABLED
}
#
# [OPTIONAL] Zeroconf for UDP links
......
......@@ -43,12 +43,15 @@ import android.content.IntentFilter;
import android.hardware.usb.*;
import android.widget.Toast;
import android.util.Log;
//-- Text To Speech
import android.os.Bundle;
import android.speech.tts.TextToSpeech;
import com.hoho.android.usbserial.driver.*;
import org.qtproject.qt5.android.bindings.QtActivity;
import org.qtproject.qt5.android.bindings.QtApplication;
public class UsbDeviceJNI extends QtActivity
public class UsbDeviceJNI extends QtActivity implements TextToSpeech.OnInitListener
{
public static int BAD_PORT = 0;
private static UsbDeviceJNI m_instance;
......@@ -61,6 +64,7 @@ public class UsbDeviceJNI extends QtActivity
private BroadcastReceiver m_UsbReceiver = null;
private final static ExecutorService m_Executor = Executors.newSingleThreadExecutor();
private static final String TAG = "QGC_UsbDeviceJNI";
private static TextToSpeech m_tts;
private final static UsbIoManager.Listener m_Listener =
new UsbIoManager.Listener()
......@@ -98,6 +102,34 @@ public class UsbDeviceJNI extends QtActivity
Log.i(TAG, "Instance created");
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////
//
// Text To Speech
// Pigback a ride for providing TTS to QGC
//
/////////////////////////////////////////////////////////////////////////////////////////////////////////
@Override
public void onCreate(Bundle savedInstanceState) {
super.onCreate(savedInstanceState);
m_tts = new TextToSpeech(this,this);
}
@Override
protected void onDestroy() {
super.onDestroy();
m_tts.shutdown();
}
public void onInit(int status) {
}
public static void say(String msg)
{
Log.i(TAG, "Say: " + msg);
m_tts.speak(msg, TextToSpeech.QUEUE_FLUSH, null);
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////
//
// Find all current devices that match the device filter described in the androidmanifest.xml and the
......
......@@ -38,42 +38,51 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h"
#include "QGC.h"
#if defined __android__
#include <QtAndroidExtras/QtAndroidExtras>
#include <QtAndroidExtras/QAndroidJniObject>
#endif
IMPLEMENT_QGC_SINGLETON(GAudioOutput, GAudioOutput)
const char* GAudioOutput::_mutedKey = "AudioMuted";
GAudioOutput::GAudioOutput(QObject *parent) :
QGCSingleton(parent),
muted(false),
thread(new QThread()),
worker(new QGCAudioWorker())
GAudioOutput::GAudioOutput(QObject *parent)
: QGCSingleton(parent)
, muted(false)
#ifndef __android__
, thread(new QThread())
, worker(new QGCAudioWorker())
#endif
{
QSettings settings;
muted = settings.value(_mutedKey, false).toBool();
muted |= qgcApp()->runningUnitTests();
#ifndef __android__
worker->moveToThread(thread);
connect(this, &GAudioOutput::textToSpeak, worker, &QGCAudioWorker::say);
connect(thread, &QThread::finished, thread, &QObject::deleteLater);
connect(thread, &QThread::finished, worker, &QObject::deleteLater);
thread->start();
#endif
}
GAudioOutput::~GAudioOutput()
{
#ifndef __android__
thread->quit();
#endif
}
void GAudioOutput::mute(bool mute)
{
QSettings settings;
muted = mute;
settings.setValue(_mutedKey, mute);
#ifndef __android__
emit mutedChanged(mute);
#endif
}
bool GAudioOutput::isMuted()
......@@ -81,10 +90,24 @@ bool GAudioOutput::isMuted()
return muted;
}
bool GAudioOutput::say(const QString& text, int severity)
bool GAudioOutput::say(const QString& inText, int severity)
{
if (!muted) {
emit textToSpeak(text, severity);
#if defined __android__
#if defined QGC_SPEECH_ENABLED
static const char V_jniClassName[] {"org/qgroundcontrol/qgchelper/UsbDeviceJNI"};
QAndroidJniEnvironment env;
if (env->ExceptionCheck()) {
env->ExceptionDescribe();
env->ExceptionClear();
}
QString text = QGCAudioWorker::fixTextMessageForAudio(inText);
QAndroidJniObject javaMessage = QAndroidJniObject::fromString(text);
QAndroidJniObject::callStaticMethod<void>(V_jniClassName, "say", "(Ljava/lang/String;)V", javaMessage.object<jstring>());
#endif
#else
emit textToSpeak(inText, severity);
#endif
}
return true;
}
......@@ -48,9 +48,9 @@ This file is part of the PIXHAWK project
class GAudioOutput : public QGCSingleton
{
Q_OBJECT
DECLARE_QGC_SINGLETON(GAudioOutput, GAudioOutput)
public:
/** @brief List available voices */
QStringList listVoices(void);
......@@ -88,13 +88,16 @@ signals:
protected:
bool muted;
#if !defined __android__
QThread* thread;
QGCAudioWorker* worker;
#endif
private:
GAudioOutput(QObject *parent = NULL);
~GAudioOutput();
static const char* _mutedKey;
};
......
......@@ -10,6 +10,47 @@
#if defined Q_OS_MAC && defined QGC_SPEECH_ENABLED
#include <ApplicationServices/ApplicationServices.h>
static SpeechChannel sc;
static Fixed volume;
static void speechDone(SpeechChannel sc2, void *) {
if (sc2 == sc)
{
DisposeSpeechChannel(sc);
}
}
class MacSpeech
{
public:
MacSpeech()
{
setVolume(100);
}
~MacSpeech()
{
}
void say(const char* words)
{
while (SpeechBusy()) {
QGC::SLEEP::msleep(100);
}
NewSpeechChannel(NULL, &sc);
SetSpeechInfo(sc, soVolume, &volume);
SetSpeechInfo(sc, soSpeechDoneCallBack, reinterpret_cast<void *>(speechDone));
CFStringRef cfstr = CFStringCreateWithCString(NULL, words, kCFStringEncodingUTF8);
SpeakCFString(sc, cfstr, NULL);
}
void setVolume(int v)
{
volume = FixRatio(v, 100);
}
};
//-- Singleton
MacSpeech macSpeech;
#endif
// Speech synthesis is only supported with MSVC compiler
......@@ -18,7 +59,7 @@
#include <sapi.h>
#endif
#if defined Q_OS_LINUX && defined QGC_SPEECH_ENABLED
#if defined Q_OS_LINUX && !defined __android__ && defined QGC_SPEECH_ENABLED
// Using eSpeak for speech synthesis: following https://github.com/mondhs/espeak-sample/blob/master/sampleSpeak.cpp
#include <espeak/speak_lib.h>
#endif
......@@ -48,7 +89,7 @@ void QGCAudioWorker::init()
sound = new QSound(":/res/Alert");
#endif
#if defined Q_OS_LINUX && defined QGC_SPEECH_ENABLED
#if defined Q_OS_LINUX && !defined __android__ && defined QGC_SPEECH_ENABLED
espeak_Initialize(AUDIO_OUTPUT_SYNCH_PLAYBACK, 500, NULL, 0); // initialize for playback with 500ms buffer and no options (see speak_lib.h)
espeak_VOICE *espeak_voice = espeak_GetCurrentVoice();
espeak_voice->languages = "en-uk"; // Default to British English
......@@ -82,25 +123,29 @@ void QGCAudioWorker::init()
QGCAudioWorker::~QGCAudioWorker()
{
#if defined _MSC_VER && defined QGC_SPEECH_ENABLED
if (pVoice) {
pVoice->Release();
pVoice = NULL;
}
if (pVoice) {
pVoice->Release();
pVoice = NULL;
}
::CoUninitialize();
#endif
}
void QGCAudioWorker::say(QString inText, int severity)
{
static bool threadInit = false;
if (!threadInit) {
threadInit = true;
init();
}
#ifdef __android__
Q_UNUSED(inText);
Q_UNUSED(severity);
#else
static bool threadInit = false;
if (!threadInit) {
threadInit = true;
init();
}
if (!muted)
{
QString text = _fixTextMessageForAudio(inText);
QString text = fixTextMessageForAudio(inText);
// Prepend high priority text with alert beep
if (severity < GAudioOutput::AUDIO_SEVERITY_CRITICAL) {
beep();
......@@ -115,35 +160,22 @@ void QGCAudioWorker::say(QString inText, int severity)
#if defined _MSC_VER && defined QGC_SPEECH_ENABLED
HRESULT hr = pVoice->Speak(text.toStdWString().c_str(), SPF_DEFAULT, NULL);
if (FAILED(hr)) {
qDebug() << "Speak failed, HR:" << QString("%1").arg(hr, 0, 16);
}
if (FAILED(hr)) {
qDebug() << "Speak failed, HR:" << QString("%1").arg(hr, 0, 16);
}
#elif defined Q_OS_LINUX && defined QGC_SPEECH_ENABLED
// Set size of string for espeak: +1 for the null-character
unsigned int espeak_size = strlen(text.toStdString().c_str()) + 1;
espeak_Synth(text.toStdString().c_str(), espeak_size, 0, POS_CHARACTER, 0, espeakCHARS_AUTO, NULL, NULL);
#elif defined Q_OS_MAC && defined QGC_SPEECH_ENABLED
// Slashes necessary to have the right start to the sentence
// copying data prevents SpeakString from reading additional chars
text = "\\" + text;
std::wstring str = text.toStdWString();
unsigned char str2[1024] = {};
memcpy(str2, text.toLatin1().data(), str.length());
SpeakString(str2);
// Block the thread while busy
// because we run in our own thread, this doesn't
// halt the main application
while (SpeechBusy()) {
QGC::SLEEP::msleep(100);
}
macSpeech.say(text.toStdString().c_str());
#else
// Make sure there isn't an unused variable warning when speech output is disabled
Q_UNUSED(inText);
#endif
}
#endif // __android__
}
void QGCAudioWorker::mute(bool mute)
......@@ -187,7 +219,7 @@ bool QGCAudioWorker::_getMillisecondString(const QString& string, QString& match
return false;
}
QString QGCAudioWorker::_fixTextMessageForAudio(const QString& string) {
QString QGCAudioWorker::fixTextMessageForAudio(const QString& string) {
QString match;
QString newNumber;
QString result = string;
......@@ -204,7 +236,9 @@ QString QGCAudioWorker::_fixTextMessageForAudio(const QString& string) {
if(result.contains("ALTCTL", Qt::CaseInsensitive)) {
result.replace("ALTCTL", "Altitude Control", Qt::CaseInsensitive);
}
if(result.contains("RTL", Qt::CaseInsensitive)) {
if(result.contains("AUTO_RTL", Qt::CaseInsensitive)) {
result.replace("AUTO_RTL", "auto Return To Land", Qt::CaseInsensitive);
} else if(result.contains("RTL", Qt::CaseInsensitive)) {
result.replace("RTL", "Return To Land", Qt::CaseInsensitive);
}
if(result.contains("ACCEL ", Qt::CaseInsensitive)) {
......
......@@ -7,13 +7,6 @@
#include <QSound>
#endif
/* For Snow leopard and later
#if defined Q_OS_MAC & defined QGC_SPEECH_ENABLED
#include <NSSpeechSynthesizer.h>
#endif
*/
#if defined _MSC_VER && defined QGC_SPEECH_ENABLED
// Documentation: http://msdn.microsoft.com/en-us/library/ee125082%28v=VS.85%29.aspx
#include <basetyps.h>
......@@ -31,6 +24,8 @@ public:
bool isMuted();
void init();
static QString fixTextMessageForAudio(const QString& string);
signals:
public slots:
......@@ -52,8 +47,7 @@ protected:
QTimer *emergencyTimer;
bool muted;
private:
QString _fixTextMessageForAudio(const QString& string);
bool _getMillisecondString(const QString& string, QString& match, int& number);
static bool _getMillisecondString(const QString& string, QString& match, int& number);
};
#endif // QGCAUDIOWORKER_H
......@@ -179,7 +179,7 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle) : UASInterface(),
lastSendTimeOpticalFlow(0),
_vehicle(vehicle)
{
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
......@@ -422,7 +422,7 @@ void UAS::receiveMessage(mavlink_message_t message)
modechanged = true;
this->base_mode = state.base_mode;
this->custom_mode = state.custom_mode;
modeAudio = " is now in " + audiomodeText + "flight mode";
modeAudio = " is now in " + audiomodeText + " flight mode";
}
// We got the mode
......@@ -945,7 +945,7 @@ void UAS::receiveMessage(mavlink_message_t message)
emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
}
break;
case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
{
if (multiComponentSourceDetected && wrongComponent)
......@@ -970,14 +970,14 @@ void UAS::receiveMessage(mavlink_message_t message)
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
// Ensure NUL-termination
b[b.length()-1] = '\0';
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
{
text.remove("#");
......@@ -1127,14 +1127,14 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType)
if (!_vehicle) {
return;
}
int gyroCal = 0;
int magCal = 0;
int airspeedCal = 0;
int radioCal = 0;
int accelCal = 0;
int escCal = 0;
switch (calType) {
case StartCalibrationGyro:
gyroCal = 1;
......@@ -1164,7 +1164,7 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType)
escCal = 2;
break;
}
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
......@@ -1188,7 +1188,7 @@ void UAS::stopCalibration(void)
if (!_vehicle) {
return;
}
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
......@@ -1212,7 +1212,7 @@ void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
if (!_vehicle) {
return;
}
int actuatorCal = 0;
switch (calType) {
......@@ -1247,7 +1247,7 @@ void UAS::stopBusConfig(void)
if (!_vehicle) {
return;
}
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
......@@ -1518,7 +1518,7 @@ void UAS::requestImage()
if (!_vehicle) {
return;
}
qDebug() << "trying to get an image from the uas...";
// check if there is already an image transmission going on
......@@ -1605,7 +1605,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
case MAV_PARAM_TYPE_UINT32:
paramValue = QVariant(paramUnion.param_uint32);
break;
case MAV_PARAM_TYPE_INT32:
paramValue = QVariant(paramUnion.param_int32);
break;
......@@ -1658,7 +1658,7 @@ void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float
if (!_vehicle) {
return;
}
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = (uint16_t)command;
......@@ -1686,7 +1686,7 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
if (!_vehicle) {
return;
}
// Store the previous manual commands
static float manualRollAngle = 0.0;
static float manualPitchAngle = 0.0;
......@@ -1843,7 +1843,7 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
// Store scaling values for all 3 axes
const float axesScaling = 1.0 * 1000.0;
// Calculate the new commands for roll, pitch, yaw, and thrust
const float newRollCommand = roll * axesScaling;
// negate pitch value because pitch is negative for pitching forward but mavlink message argument is positive for forward
......@@ -1852,7 +1852,7 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
const float newThrustCommand = thrust * axesScaling;
//qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
// Send the MANUAL_COMMAND message
mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
}
......@@ -1870,7 +1870,7 @@ void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll
if (!_vehicle) {
return;
}
// If system has manual inputs enabled and is armed
if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
{
......@@ -1935,7 +1935,7 @@ void UAS::pairRX(int rxType, int rxSubType)
if (!_vehicle) {
return;
}
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_START_RX_PAIR, 0, rxType, rxSubType, 0, 0, 0, 0, 0);
......@@ -2138,7 +2138,7 @@ void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, floa
if (!_vehicle) {
return;
}
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
{
float q[4];
......@@ -2176,12 +2176,12 @@ void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, floa
#ifndef __mobile__
float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
{
/* Calculate normally distributed variable noise with mean = 0 and variance = noise_var. Calculated according to
/* Calculate normally distributed variable noise with mean = 0 and variance = noise_var. Calculated according to
Box-Muller transform */
static const float epsilon = std::numeric_limits<float>::min(); //used to ensure non-zero uniform numbers
static float z0; //calculated normal distribution random variables with mu = 0, var = 1;
float u1, u2; //random variables generated from c++ rand();
/*Generate random variables in range (0 1] */
do
{
......@@ -2193,11 +2193,11 @@ float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
while ( u1 <= epsilon ); //Have a catch to ensure non-zero for log()
z0 = sqrt(-2.0 * log(u1)) * cos(2.0f * M_PI * u2); //calculate normally distributed variable with mu = 0, var = 1
//TODO add bias term that changes randomly to simulate accelerometer and gyro bias the exf should handle these
//as well
float noise = z0 * sqrt(noise_var); //calculate normally distributed variable with mu = 0, std = var^2
//Finally gaurd against any case where the noise is not real
if(std::isfinite(noise)) {
return truth_meas + noise;
......@@ -2218,7 +2218,7 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl
if (!_vehicle) {
return;
}
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
{
float xacc_corrupt = addZeroMeanNoise(xacc, xacc_var);
......@@ -2238,7 +2238,7 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl
mavlink_message_t msg;
mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, xacc_corrupt, yacc_corrupt, zacc_corrupt, rollspeed_corrupt, pitchspeed_corrupt,
yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
diff_pressure_corrupt, pressure_alt_corrupt, temperature_corrupt, fields_changed);
_vehicle->sendMessage(msg);
lastSendTimeSensors = QGC::groundTimeMilliseconds();
......@@ -2259,7 +2259,7 @@ void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, floa
if (!_vehicle) {
return;
}
// FIXME: This needs to be updated for new mavlink_msg_hil_optical_flow_pack api
Q_UNUSED(time_us);
......@@ -2297,7 +2297,7 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi
if (!_vehicle) {
return;
}
// Only send at 10 Hz max rate
if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
return;
......@@ -2413,7 +2413,7 @@ void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 p
if (!_vehicle) {
return;
}
mavlink_message_t message;
char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
......@@ -2447,7 +2447,7 @@ void UAS::unsetRCToParameterMap()
if (!_vehicle) {
return;
}
char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
for (int i = 0; i < 3; i++) {
......@@ -2470,10 +2470,6 @@ void UAS::unsetRCToParameterMap()
void UAS::_say(const QString& text, int severity)
{
#ifndef UNITTEST_BUILD
GAudioOutput::instance()->say(text, severity);
#else
Q_UNUSED(text)
Q_UNUSED(severity)
#endif
if (!qgcApp()->runningUnitTests())
GAudioOutput::instance()->say(text, severity);
}
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