Commit c67c2784 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #199 from skye-git/default_3DMouse

3 d mouse
parents 7b1df3b8 b9864c1f
......@@ -47,6 +47,8 @@ user_config.pri
*.cproject
*.sln
*.suo
*.uhf.txt
*.opensdf
thirdParty/qserialport-build-desktop/
thirdParty/qserialport/bin/
......
#ifndef I3D_MOUSE_PARAMS_H
#define I3D_MOUSE_PARAMS_H
/*
Parameters for the 3D mouse based on the SDK from 3Dconnexion
*/
class I3dMouseSensor
{
public:
enum ESpeed {
kLowSpeed = 0,
kMidSpeed,
kHighSpeed
};
virtual bool IsPanZoom() const = 0;
virtual bool IsRotate() const = 0;
virtual ESpeed GetSpeed() const = 0;
virtual void SetPanZoom(bool isPanZoom) = 0;
virtual void SetRotate(bool isRotate) = 0;
virtual void SetSpeed(ESpeed speed) = 0;
protected:
virtual ~I3dMouseSensor() {}
};
class I3dMouseNavigation
{
public:
enum EPivot {
kManualPivot = 0,
kAutoPivot,
kAutoPivotOverride
};
enum ENavigation {
kObjectMode = 0,
kCameraMode,
kFlyMode,
kWalkMode,
kHelicopterMode
};
enum EPivotVisibility {
kHidePivot = 0,
kShowPivot,
kShowMovingPivot
};
virtual ENavigation GetNavigationMode() const = 0;
virtual EPivot GetPivotMode() const = 0;
virtual EPivotVisibility GetPivotVisibility() const = 0;
virtual bool IsLockHorizon() const = 0;
virtual void SetLockHorizon(bool bOn) = 0;
virtual void SetNavigationMode(ENavigation navigation) = 0;
virtual void SetPivotMode(EPivot pivot) = 0;
virtual void SetPivotVisibility(EPivotVisibility visibility) = 0;
protected:
virtual ~I3dMouseNavigation(){}
};
class I3dMouseParam : public I3dMouseSensor, public I3dMouseNavigation
{
public:
virtual ~I3dMouseParam() {}
};
#endif
#include "Mouse3DInput.h"
#include <QApplication>
#define LOGITECH_VENDOR_ID 0x46d
#define _CONSTANT_INPUT_PERIOD 0
#ifndef RIDEV_DEVNOTIFY
#define RIDEV_DEVNOTIFY 0x00002000
#endif
#define _TRACE_WM_INPUT_PERIOD 0
#define _TRACE_RI_TYPE 0
#define _TRACE_RIDI_DEVICENAME 0
#define _TRACE_RIDI_DEVICEINFO 0
#define _TRACE_RI_RAWDATA 0
#define _TRACE_3DINPUT_PERIOD 0
#ifdef _WIN64
typedef unsigned __int64 QWORD;
#endif
// object angular velocity per mouse tick 0.008 milliradians per second per count
static const double k3dmouseAngularVelocity = 8.0e-6; // radians per second per count
static const int kTimeToLive = 5;
enum e3dconnexion_pid {
eSpacePilot = 0xc625,
eSpaceNavigator = 0xc626,
eSpaceExplorer = 0xc627,
eSpaceNavigatorForNotebooks = 0xc628,
eSpacePilotPRO = 0xc629
};
enum e3dmouse_virtual_key
{
V3DK_INVALID=0
, V3DK_MENU=1, V3DK_FIT
, V3DK_TOP, V3DK_LEFT, V3DK_RIGHT, V3DK_FRONT, V3DK_BOTTOM, V3DK_BACK
, V3DK_CW, V3DK_CCW
, V3DK_ISO1, V3DK_ISO2
, V3DK_1, V3DK_2, V3DK_3, V3DK_4, V3DK_5, V3DK_6, V3DK_7, V3DK_8, V3DK_9, V3DK_10
, V3DK_ESC, V3DK_ALT, V3DK_SHIFT, V3DK_CTRL
, V3DK_ROTATE, V3DK_PANZOOM, V3DK_DOMINANT
, V3DK_PLUS, V3DK_MINUS
};
struct tag_VirtualKeys
{
e3dconnexion_pid pid;
size_t nKeys;
e3dmouse_virtual_key *vkeys;
};
static const e3dmouse_virtual_key SpaceExplorerKeys [] =
{
V3DK_INVALID // there is no button 0
, V3DK_1, V3DK_2
, V3DK_TOP, V3DK_LEFT, V3DK_RIGHT, V3DK_FRONT
, V3DK_ESC, V3DK_ALT, V3DK_SHIFT, V3DK_CTRL
, V3DK_FIT, V3DK_MENU
, V3DK_PLUS, V3DK_MINUS
, V3DK_ROTATE
};
static const e3dmouse_virtual_key SpacePilotKeys [] =
{
V3DK_INVALID
, V3DK_1, V3DK_2, V3DK_3, V3DK_4, V3DK_5, V3DK_6
, V3DK_TOP, V3DK_LEFT, V3DK_RIGHT, V3DK_FRONT
, V3DK_ESC, V3DK_ALT, V3DK_SHIFT, V3DK_CTRL
, V3DK_FIT, V3DK_MENU
, V3DK_PLUS, V3DK_MINUS
, V3DK_DOMINANT, V3DK_ROTATE
};
static const struct tag_VirtualKeys _3dmouseVirtualKeys[]=
{
eSpacePilot
, sizeof(SpacePilotKeys)/sizeof(SpacePilotKeys[0])
, const_cast<e3dmouse_virtual_key *>(SpacePilotKeys),
eSpaceExplorer
, sizeof(SpaceExplorerKeys)/sizeof(SpaceExplorerKeys[0])
, const_cast<e3dmouse_virtual_key *>(SpaceExplorerKeys)
};
/*!
Converts a hid device keycode (button identifier) of a pre-2009 3Dconnexion USB device to the standard 3d mouse virtual key definition.
\a pid USB Product ID (PID) of 3D mouse device
\a hidKeyCode Hid keycode as retrieved from a Raw Input packet
\return The standard 3d mouse virtual key (button identifier) or zero if an error occurs.
Converts a hid device keycode (button identifier) of a pre-2009 3Dconnexion USB device
to the standard 3d mouse virtual key definition.
*/
unsigned short HidToVirtualKey(unsigned long pid, unsigned short hidKeyCode)
{
unsigned short virtualkey=hidKeyCode;
for (size_t i=0; i<sizeof(_3dmouseVirtualKeys)/sizeof(_3dmouseVirtualKeys[0]); ++i)
{
if (pid == _3dmouseVirtualKeys[i].pid)
{
if (hidKeyCode < _3dmouseVirtualKeys[i].nKeys)
virtualkey = _3dmouseVirtualKeys[i].vkeys[hidKeyCode];
else
virtualkey = V3DK_INVALID;
break;
}
}
// Remaining devices are unchanged
return virtualkey;
}
static Mouse3DInput* gMouseInput = 0;
bool Mouse3DInput::RawInputEventFilter(void* msg, long* result)
{
if (gMouseInput == 0) return false;
MSG* message = (MSG*)(msg);
if (message->message == WM_INPUT) {
HRAWINPUT hRawInput = reinterpret_cast<HRAWINPUT>(message->lParam);
gMouseInput->OnRawInput(RIM_INPUT,hRawInput);
if (result != 0) {
result = 0;
}
return true;
}
return false;
}
Mouse3DInput::Mouse3DInput(QWidget* widget) :
QObject(widget)
{
fLast3dmouseInputTime = 0;
InitializeRawInput(widget->winId());
gMouseInput = this;
qApp->setEventFilter(Mouse3DInput::RawInputEventFilter);
}
Mouse3DInput::~Mouse3DInput()
{
if (gMouseInput == this) {
gMouseInput = 0;
}
}
/*!
Access the mouse parameters structure
*/
I3dMouseParam& Mouse3DInput::MouseParams()
{
return f3dMouseParams;
}
/*!
Access the mouse parameters structure
*/
const I3dMouseParam& Mouse3DInput::MouseParams() const
{
return f3dMouseParams;
}
/*!
Called with the processed motion data when a 3D mouse event is received
The default implementation emits a Move3d signal with the motion data
*/
void Mouse3DInput::Move3d(HANDLE device, std::vector<float>& motionData)
{
Q_UNUSED(device);
emit Move3d(motionData);
}
/*!
Called when a 3D mouse key is pressed
The default implementation emits a On3dmouseKeyDown signal with the key code.
*/
void Mouse3DInput::On3dmouseKeyDown(HANDLE device, int virtualKeyCode)
{
Q_UNUSED(device);
emit On3dmouseKeyDown(virtualKeyCode);
}
/*!
Called when a 3D mouse key is released
The default implementation emits a On3dmouseKeyUp signal with the key code.
*/
void Mouse3DInput::On3dmouseKeyUp(HANDLE device, int virtualKeyCode)
{
Q_UNUSED(device);
emit On3dmouseKeyUp(virtualKeyCode);
}
/*!
Get an initialized array of PRAWINPUTDEVICE for the 3D devices
pNumDevices returns the number of devices to register. Currently this is always 1.
*/
static PRAWINPUTDEVICE GetDevicesToRegister(unsigned int* pNumDevices)
{
// Array of raw input devices to register
static RAWINPUTDEVICE sRawInputDevices[] = {
{0x01, 0x08, 0x00, 0x00} // Usage Page = 0x01 Generic Desktop Page, Usage Id= 0x08 Multi-axis Controller
};
if (pNumDevices) {
*pNumDevices = sizeof(sRawInputDevices) / sizeof(sRawInputDevices[0]);
}
return sRawInputDevices;
}
/*!
Detect the 3D mouse
*/
bool Mouse3DInput::Is3dmouseAttached()
{
unsigned int numDevicesOfInterest = 0;
PRAWINPUTDEVICE devicesToRegister = GetDevicesToRegister(&numDevicesOfInterest);
unsigned int nDevices = 0;
if (::GetRawInputDeviceList(NULL, &nDevices, sizeof(RAWINPUTDEVICELIST)) != 0) {
return false;
}
if (nDevices == 0) return false;
std::vector<RAWINPUTDEVICELIST> rawInputDeviceList(nDevices);
if (::GetRawInputDeviceList(&rawInputDeviceList[0], &nDevices, sizeof(RAWINPUTDEVICELIST)) == static_cast<unsigned int>(-1)) {
return false;
}
for (unsigned int i = 0; i < nDevices; ++i) {
RID_DEVICE_INFO rdi = {sizeof(rdi)};
unsigned int cbSize = sizeof(rdi);
if (GetRawInputDeviceInfo(rawInputDeviceList[i].hDevice, RIDI_DEVICEINFO, &rdi, &cbSize) > 0) {
//skip non HID and non logitec (3DConnexion) devices
if (rdi.dwType != RIM_TYPEHID || rdi.hid.dwVendorId != LOGITECH_VENDOR_ID) {
continue;
}
//check if devices matches Multi-axis Controller
for (unsigned int j = 0; j < numDevicesOfInterest; ++j) {
if (devicesToRegister[j].usUsage == rdi.hid.usUsage
&& devicesToRegister[j].usUsagePage == rdi.hid.usUsagePage) {
return true;
}
}
}
}
return false;
}
/*!
Initialize the window to recieve raw-input messages
This needs to be called initially so that Windows will send the messages from the 3D mouse to the window.
*/
bool Mouse3DInput::InitializeRawInput(HWND hwndTarget)
{
fWindow = hwndTarget;
// Simply fail if there is no window
if (!hwndTarget) return false;
unsigned int numDevices = 0;
PRAWINPUTDEVICE devicesToRegister = GetDevicesToRegister(&numDevices);
if (numDevices == 0) return false;
// Get OS version.
OSVERSIONINFO osvi = {sizeof(OSVERSIONINFO),0};
::GetVersionEx(&osvi);
unsigned int cbSize = sizeof (devicesToRegister[0]);
for (size_t i = 0; i < numDevices; i++) {
// Set the target window to use
//devicesToRegister[i].hwndTarget = hwndTarget;
// If Vista or newer, enable receiving the WM_INPUT_DEVICE_CHANGE message.
if (osvi.dwMajorVersion >= 6) {
devicesToRegister[i].dwFlags |= RIDEV_DEVNOTIFY;
}
}
return (::RegisterRawInputDevices(devicesToRegister, numDevices, cbSize) != FALSE);
}
/*!
Get the raw input data from Windows
Includes workaround for incorrect alignment of the RAWINPUT structure on x64 os
when running as Wow64 (copied directly from 3DConnexion code)
*/
UINT Mouse3DInput::GetRawInputBuffer(PRAWINPUT pData, PUINT pcbSize, UINT cbSizeHeader)
{
#ifdef _WIN64
return ::GetRawInputBuffer(pData, pcbSize, cbSizeHeader);
#else
BOOL bIsWow64 = FALSE;
::IsWow64Process(GetCurrentProcess(), &bIsWow64);
if (!bIsWow64 || pData==NULL) {
return ::GetRawInputBuffer(pData, pcbSize, cbSizeHeader);
} else {
HWND hwndTarget = fWindow; //fParent->winId();
size_t cbDataSize=0;
UINT nCount=0;
PRAWINPUT pri = pData;
MSG msg;
while (PeekMessage(&msg, hwndTarget, WM_INPUT, WM_INPUT, PM_NOREMOVE)) {
HRAWINPUT hRawInput = reinterpret_cast<HRAWINPUT>(msg.lParam);
size_t cbSize = *pcbSize - cbDataSize;
if (::GetRawInputData(hRawInput, RID_INPUT, pri, &cbSize, cbSizeHeader) == static_cast<UINT>(-1)) {
if (nCount==0) {
return static_cast<UINT>(-1);
} else {
break;
}
}
++nCount;
// Remove the message for the data just read
PeekMessage(&msg, hwndTarget, WM_INPUT, WM_INPUT, PM_REMOVE);
pri = NEXTRAWINPUTBLOCK(pri);
cbDataSize = reinterpret_cast<ULONG_PTR>(pri) - reinterpret_cast<ULONG_PTR>(pData);
if (cbDataSize >= *pcbSize) {
cbDataSize = *pcbSize;
break;
}
}
return nCount;
}
#endif
}
/*!
Process the raw input device data
On3dmouseInput() does all the preprocessing of the rawinput device data before
finally calling the Move3d method.
*/
void Mouse3DInput::On3dmouseInput()
{
// Don't do any data processing in background
bool bIsForeground = (::GetActiveWindow() != NULL);
if (!bIsForeground) {
// set all cached data to zero so that a zero event is seen and the cached data deleted
for (std::map<HANDLE, TInputData>::iterator it = fDevice2Data.begin(); it != fDevice2Data.end(); it++) {
it->second.fAxes.assign(6, .0);
it->second.fIsDirty = true;
}
}
DWORD dwNow = ::GetTickCount(); // Current time;
DWORD dwElapsedTime; // Elapsed time since we were last here
if (0 == fLast3dmouseInputTime) {
dwElapsedTime = 10; // System timer resolution
} else {
dwElapsedTime = dwNow - fLast3dmouseInputTime;
if (fLast3dmouseInputTime > dwNow) {
dwElapsedTime = ~dwElapsedTime+1;
}
if (dwElapsedTime<1) {
dwElapsedTime=1;
} else if (dwElapsedTime > 500) {
// Check for wild numbers because the device was removed while sending data
dwElapsedTime = 10;
}
}
#if _TRACE_3DINPUT_PERIOD
qDebug("On3DmouseInput() period is %dms\n", dwElapsedTime);
#endif
float mouseData2Rotation = k3dmouseAngularVelocity;
// v = w * r, we don't know r yet so lets assume r=1.)
float mouseData2PanZoom = k3dmouseAngularVelocity;
// Grab the I3dmouseParam interface
I3dMouseParam& i3dmouseParam = f3dMouseParams;
// Take a look at the users preferred speed setting and adjust the sensitivity accordingly
I3dMouseSensor::ESpeed speedSetting = i3dmouseParam.GetSpeed();
// See "Programming for the 3D Mouse", Section 5.1.3
float speed = (speedSetting == I3dMouseSensor::kLowSpeed ? 0.25f : speedSetting == I3dMouseSensor::kHighSpeed ? 4.f : 1.f);
// Multiplying by the following will convert the 3d mouse data to real world units
mouseData2PanZoom *= speed;
mouseData2Rotation *= speed;
std::map<HANDLE, TInputData>::iterator iterator=fDevice2Data.begin();
while (iterator != fDevice2Data.end()) {
// If we have not received data for a while send a zero event
if ((--(iterator->second.fTimeToLive)) == 0) {
iterator->second.fAxes.assign(6, .0);
} else if (/*!t_bPoll3dmouse &&*/ !iterator->second.fIsDirty) {
// If we are not polling then only handle the data that was actually received
++iterator;
continue;
}
iterator->second.fIsDirty=false;
// get a copy of the device
HANDLE hdevice = iterator->first;
// get a copy of the motion vectors and apply the user filters
std::vector<float> motionData = iterator->second.fAxes;
// apply the user filters
// Pan Zoom filter
// See "Programming for the 3D Mouse", Section 5.1.2
if (!i3dmouseParam.IsPanZoom()) {
// Pan zoom is switched off so set the translation vector values to zero
motionData[0] = motionData[1] = motionData[2] = 0.;
}
// Rotate filter
// See "Programming for the 3D Mouse", Section 5.1.1
if (!i3dmouseParam.IsRotate()) {
// Rotate is switched off so set the rotation vector values to zero
motionData[3] = motionData[4] = motionData[5] = 0.;
}
// convert the translation vector into physical data
for (int axis = 0; axis < 3; axis++) {
motionData[axis] *= mouseData2PanZoom;
}
// convert the directed Rotate vector into physical data
// See "Programming for the 3D Mouse", Section 7.2.2
for (int axis = 3; axis < 6; axis++) {
motionData[axis] *= mouseData2Rotation;
}
// Now that the data has had the filters and sensitivty settings applied
// calculate the displacements since the last view update
for (int axis = 0; axis < 6; axis++) {
motionData[axis] *= dwElapsedTime;
}
// Now a bit of book keeping before passing on the data
if (iterator->second.IsZero()) {
iterator = fDevice2Data.erase(iterator);
} else {
++iterator;
}
// Work out which will be the next device
HANDLE hNextDevice = 0;
if (iterator != fDevice2Data.end()) {
hNextDevice = iterator->first;
}
// Pass the 3dmouse input to the view controller
Move3d(hdevice, motionData);
// Because we don't know what happened in the previous call, the cache might have
// changed so reload the iterator
iterator = fDevice2Data.find(hNextDevice);
}
if (!fDevice2Data.empty()) {
fLast3dmouseInputTime = dwNow;
} else {
fLast3dmouseInputTime = 0;
}
}
/*!
Called when new raw input data is available
*/
void Mouse3DInput::OnRawInput(UINT nInputCode, HRAWINPUT hRawInput)
{
const size_t cbSizeOfBuffer=1024;
BYTE pBuffer[cbSizeOfBuffer];
PRAWINPUT pRawInput = reinterpret_cast<PRAWINPUT>(pBuffer);
UINT cbSize = cbSizeOfBuffer;
if (::GetRawInputData(hRawInput, RID_INPUT, pRawInput, &cbSize, sizeof(RAWINPUTHEADER)) == static_cast<UINT>(-1)) {
return;
}
bool b3dmouseInput = TranslateRawInputData(nInputCode, pRawInput);
::DefRawInputProc(&pRawInput, 1, sizeof(RAWINPUTHEADER));
// Check for any buffered messages
cbSize = cbSizeOfBuffer;
UINT nCount = this->GetRawInputBuffer(pRawInput, &cbSize, sizeof(RAWINPUTHEADER));
if (nCount == (UINT)-1) {
qDebug ("GetRawInputBuffer returned error %d\n", GetLastError());
}
while (nCount>0 && nCount != static_cast<UINT>(-1)) {
PRAWINPUT pri = pRawInput;
UINT nInput;
for (nInput=0; nInput<nCount; ++nInput) {
b3dmouseInput |= TranslateRawInputData(nInputCode, pri);
// clean the buffer
::DefRawInputProc(&pri, 1, sizeof(RAWINPUTHEADER));
pri = NEXTRAWINPUTBLOCK(pri);
}
cbSize = cbSizeOfBuffer;
nCount = this->GetRawInputBuffer(pRawInput, &cbSize, sizeof(RAWINPUTHEADER));
}
// If we have mouse input data for the app then tell tha app about it
if (b3dmouseInput) {
On3dmouseInput();
}
}
bool Mouse3DInput::TranslateRawInputData(UINT nInputCode, PRAWINPUT pRawInput)
{
bool bIsForeground = (nInputCode == RIM_INPUT);
#if _TRACE_RI_TYPE
qDebug("Rawinput.header.dwType=0x%x\n", pRawInput->header.dwType);
#endif
// We are not interested in keyboard or mouse data received via raw input
if (pRawInput->header.dwType != RIM_TYPEHID) return false;
#if _TRACE_RIDI_DEVICENAME
UINT dwSize=0;
if (::GetRawInputDeviceInfo(pRawInput->header.hDevice, RIDI_DEVICENAME, NULL, &dwSize) == 0) {
std::vector<wchar_t> szDeviceName(dwSize+1);
if (::GetRawInputDeviceInfo(pRawInput->header.hDevice, RIDI_DEVICENAME, &szDeviceName[0], &dwSize) >0) {
qDebug("Device Name = %s\nDevice handle = 0x%x\n", &szDeviceName[0], pRawInput->header.hDevice);
}
}
#endif
RID_DEVICE_INFO sRidDeviceInfo;
sRidDeviceInfo.cbSize = sizeof(RID_DEVICE_INFO);
UINT cbSize = sizeof(RID_DEVICE_INFO);
if (::GetRawInputDeviceInfo(pRawInput->header.hDevice, RIDI_DEVICEINFO, &sRidDeviceInfo, &cbSize) == cbSize) {
#if _TRACE_RIDI_DEVICEINFO
switch (sRidDeviceInfo.dwType) {
case RIM_TYPEMOUSE:
qDebug("\tsRidDeviceInfo.dwType=RIM_TYPEMOUSE\n");
break;
case RIM_TYPEKEYBOARD:
qDebug("\tsRidDeviceInfo.dwType=RIM_TYPEKEYBOARD\n");
break;
case RIM_TYPEHID:
qDebug("\tsRidDeviceInfo.dwType=RIM_TYPEHID\n");
qDebug("\tVendor=0x%x\n\tProduct=0x%x\n\tUsagePage=0x%x\n\tUsage=0x%x\n",
sRidDeviceInfo.hid.dwVendorId,
sRidDeviceInfo.hid.dwProductId,
sRidDeviceInfo.hid.usUsagePage,
sRidDeviceInfo.hid.usUsage);
break;
}
#endif
if (sRidDeviceInfo.hid.dwVendorId == LOGITECH_VENDOR_ID) {
if (pRawInput->data.hid.bRawData[0] == 0x01) { // Translation vector
TInputData& deviceData = fDevice2Data[pRawInput->header.hDevice];
deviceData.fTimeToLive = kTimeToLive;
if (bIsForeground) {
short* pnRawData = reinterpret_cast<short*>(&pRawInput->data.hid.bRawData[1]);
// Cache the pan zoom data
deviceData.fAxes[0] = static_cast<float>(pnRawData[0]);
deviceData.fAxes[1] = static_cast<float>(pnRawData[1]);
deviceData.fAxes[2] = static_cast<float>(pnRawData[2]);
#if _TRACE_RI_RAWDATA
qDebug("Pan/Zoom RI Data =\t0x%x,\t0x%x,\t0x%x\n",
pnRawData[0], pnRawData[1], pnRawData[2]);
#endif
if (pRawInput->data.hid.dwSizeHid >= 13) {// Highspeed package
// Cache the rotation data
deviceData.fAxes[3] = static_cast<float>(pnRawData[3]);
deviceData.fAxes[4] = static_cast<float>(pnRawData[4]);
deviceData.fAxes[5] = static_cast<float>(pnRawData[5]);
deviceData.fIsDirty = true;
#if _TRACE_RI_RAWDATA
qDebug("Rotation RI Data =\t0x%x,\t0x%x,\t0x%x\n",
pnRawData[3], pnRawData[4], pnRawData[5]);
#endif
return true;
}
} else { // Zero out the data if the app is not in forground
deviceData.fAxes.assign(6, 0.f);
}
} else if (pRawInput->data.hid.bRawData[0] == 0x02) { // Rotation vector
// If we are not in foreground do nothing
// The rotation vector was zeroed out with the translation vector in the previous message
if (bIsForeground) {
TInputData& deviceData = fDevice2Data[pRawInput->header.hDevice];
deviceData.fTimeToLive = kTimeToLive;
short* pnRawData = reinterpret_cast<short*>(&pRawInput->data.hid.bRawData[1]);
// Cache the rotation data
deviceData.fAxes[3] = static_cast<float>(pnRawData[0]);
deviceData.fAxes[4] = static_cast<float>(pnRawData[1]);
deviceData.fAxes[5] = static_cast<float>(pnRawData[2]);
deviceData.fIsDirty = true;
#if _TRACE_RI_RAWDATA
qDebug("Rotation RI Data =\t0x%x,\t0x%x,\t0x%x\n",
pnRawData[0], pnRawData[1], pnRawData[2]);
#endif
return true;
}
} else if (pRawInput->data.hid.bRawData[0] == 0x03) { // Keystate change
// this is a package that contains 3d mouse keystate information
// bit0=key1, bit=key2 etc.
unsigned long dwKeystate = *reinterpret_cast<unsigned long*>(&pRawInput->data.hid.bRawData[1]);
#if _TRACE_RI_RAWDATA
qDebug("ButtonData =0x%x\n", dwKeystate);
#endif
// Log the keystate changes
unsigned long dwOldKeystate = fDevice2Keystate[pRawInput->header.hDevice];
if (dwKeystate != 0) {
fDevice2Keystate[pRawInput->header.hDevice] = dwKeystate;
} else {
fDevice2Keystate.erase(pRawInput->header.hDevice);
}
// Only call the keystate change handlers if the app is in foreground
if (bIsForeground) {
unsigned long dwChange = dwKeystate ^ dwOldKeystate;
for (int nKeycode=1; nKeycode<33; nKeycode++) {
if (dwChange & 0x01) {
int nVirtualKeyCode = HidToVirtualKey(sRidDeviceInfo.hid.dwProductId, nKeycode);
if (nVirtualKeyCode) {
if (dwKeystate&0x01) {
On3dmouseKeyDown(pRawInput->header.hDevice, nVirtualKeyCode);
} else {
On3dmouseKeyUp(pRawInput->header.hDevice, nVirtualKeyCode);
}
}
}
dwChange >>=1;
dwKeystate >>=1;
}
}
}
}
}
return false;
}
#ifndef T3DMOUSE_INPUT_H
#define T3DMOUSE_INPUT_H
#include "MouseParameters.h"
#include <QWidget>
#include <vector>
#include <map>
#ifndef _WIN32_WINNT
#define _WIN32_WINNT 0x0501 //target at least windows XP
#endif
#include <windows.h>
/*
A class for connecting to and receiving data from a 3D Connexion 3D mouse
This helper class manages the connection to a 3D mouse, collecting WM_INPUT
messages from Windows and converting the data into 3D motion data.
This class is based on the SDK from 3D Connexion but is modified to work with Qt.
It is Windows only since it uses the WM_INPUT messages from windows directly
rather than Qt events.
Note that it needs to be compiled with _WIN32_WINNT defined as 0x0501 (windows XP)
or later because the raw input API was added in Windows XP. This also means that
Qt needs to be compiled with this enabled otherwise the QEventDispatcherWin32 blocks
in processEvents because the raw input messages do not cause the thread to be woken if
Qt is compiled for Win 2000 targets.
*/
class Mouse3DInput : public QObject
{
Q_OBJECT
public:
Mouse3DInput(QWidget* widget);
~Mouse3DInput();
static bool Is3dmouseAttached();
I3dMouseParam& MouseParams();
const I3dMouseParam& MouseParams() const;
virtual void Move3d(HANDLE device, std::vector<float>& motionData);
virtual void On3dmouseKeyDown(HANDLE device, int virtualKeyCode);
virtual void On3dmouseKeyUp(HANDLE device, int virtualKeyCode);
signals:
void Move3d(std::vector<float>& motionData);
void On3dmouseKeyDown(int virtualKeyCode);
void On3dmouseKeyUp(int virtualKeyCode);
private:
bool InitializeRawInput(HWND hwndTarget);
static bool RawInputEventFilter(void* msg, long* result);
void OnRawInput(UINT nInputCode, HRAWINPUT hRawInput);
UINT GetRawInputBuffer(PRAWINPUT pData, PUINT pcbSize, UINT cbSizeHeader);
bool TranslateRawInputData(UINT nInputCode, PRAWINPUT pRawInput);
void On3dmouseInput();
class TInputData
{
public:
TInputData() : fAxes(6) {}
bool IsZero() {
return (0.==fAxes[0] && 0.==fAxes[1] && 0.==fAxes[2] &&
0.==fAxes[3] && 0.==fAxes[4] && 0.==fAxes[5]);
}
int fTimeToLive; // For telling if the device was unplugged while sending data
bool fIsDirty;
std::vector<float> fAxes;
};
HWND fWindow;
// Data cache to handle multiple rawinput devices
std::map< HANDLE, TInputData> fDevice2Data;
std::map< HANDLE, unsigned long> fDevice2Keystate;
// 3dmouse parameters
MouseParameters f3dMouseParams; // Rotate, Pan Zoom etc.
// use to calculate distance traveled since last event
DWORD fLast3dmouseInputTime;
};
#endif
#include "MouseParameters.h"
MouseParameters::MouseParameters(): fNavigation(kObjectMode)
, fPivot(kAutoPivot)
, fPivotVisibility(kShowPivot)
, fIsLockHorizon(true)
, fIsPanZoom(true)
, fIsRotate(true)
, fSpeed(kLowSpeed)
{
}
MouseParameters::~MouseParameters()
{
}
bool MouseParameters::IsPanZoom() const
{
return fIsPanZoom;
}
bool MouseParameters::IsRotate() const
{
return fIsRotate;
}
MouseParameters::ESpeed MouseParameters::GetSpeed() const
{
return fSpeed;
}
void MouseParameters::SetPanZoom(bool isPanZoom)
{
fIsPanZoom=isPanZoom;
}
void MouseParameters::SetRotate(bool isRotate)
{
fIsRotate=isRotate;
}
void MouseParameters::SetSpeed(ESpeed speed)
{
fSpeed=speed;
}
MouseParameters::ENavigation MouseParameters::GetNavigationMode() const
{
return fNavigation;
}
MouseParameters::EPivot MouseParameters::GetPivotMode() const
{
return fPivot;
}
MouseParameters::EPivotVisibility MouseParameters::GetPivotVisibility() const
{
return fPivotVisibility;
}
bool MouseParameters::IsLockHorizon() const
{
return fIsLockHorizon;
}
void MouseParameters::SetLockHorizon(bool bOn)
{
fIsLockHorizon=bOn;
}
void MouseParameters::SetNavigationMode(ENavigation navigation)
{
fNavigation=navigation;
}
void MouseParameters::SetPivotMode(EPivot pivot)
{
if (fPivot!=kManualPivot || pivot!=kAutoPivotOverride)
fPivot = pivot;
}
void MouseParameters::SetPivotVisibility(EPivotVisibility visibility)
{
fPivotVisibility = visibility;
}
#ifndef T3D_MOUSE_PARAMS_H
#define T3D_MOUSE_PARAMS_H
#include "I3dMouseParams.h"
class MouseParameters : public I3dMouseParam
{
public:
MouseParameters();
~MouseParameters();
// I3dmouseSensor interface
bool IsPanZoom() const;
bool IsRotate() const;
ESpeed GetSpeed() const;
void SetPanZoom(bool isPanZoom);
void SetRotate(bool isRotate);
void SetSpeed(ESpeed speed);
// I3dmouseNavigation interface
ENavigation GetNavigationMode() const;
EPivot GetPivotMode() const;
EPivotVisibility GetPivotVisibility() const;
bool IsLockHorizon() const;
void SetLockHorizon(bool bOn);
void SetNavigationMode(ENavigation navigation);
void SetPivotMode(EPivot pivot);
void SetPivotVisibility(EPivotVisibility visibility);
private:
MouseParameters (const MouseParameters&);
const MouseParameters& operator =(const MouseParameters&);
ENavigation fNavigation;
EPivot fPivot;
EPivotVisibility fPivotVisibility;
bool fIsLockHorizon;
bool fIsPanZoom;
bool fIsRotate;
ESpeed fSpeed;
};
#endif
# -------------------------------------------------
# QGroundControl - Micro Air Vehicle Groundstation
# Please see our website at <http://qgroundcontrol.org>
# Maintainer:
# Lorenz Meier <lm@inf.ethz.ch>
# (c) 2009-2011 QGroundControl Developers
# This file is part of the open groundstation project
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
# -------------------------------------------------
# Qt configuration
CONFIG += qt \
thread
QT += network \
opengl \
svg \
xml \
phonon \
webkit \
sql
TEMPLATE = app
TARGET = qgroundcontrol
BASEDIR = $${IN_PWD}
linux-g++|linux-g++-64{
debug {
TARGETDIR = $${OUT_PWD}/debug
BUILDDIR = $${OUT_PWD}/build-debug
}
release {
TARGETDIR = $${OUT_PWD}/release
BUILDDIR = $${OUT_PWD}/build-release
}
} else {
TARGETDIR = $${OUT_PWD}
BUILDDIR = $${OUT_PWD}/build
}
LANGUAGE = C++
OBJECTS_DIR = $${BUILDDIR}/obj
MOC_DIR = $${BUILDDIR}/moc
UI_DIR = $${BUILDDIR}/ui
RCC_DIR = $${BUILDDIR}/rcc
MAVLINK_CONF = "pixhawk"
MAVLINKPATH = $$BASEDIR/libs/mavlink/include/mavlink/v1.0
DEFINES += MAVLINK_NO_DATA
win32 {
QMAKE_INCDIR_QT = $$(QTDIR)/include
QMAKE_LIBDIR_QT = $$(QTDIR)/lib
QMAKE_UIC = "$$(QTDIR)/bin/uic.exe"
QMAKE_MOC = "$$(QTDIR)/bin/moc.exe"
QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe"
QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe"
# Build QAX for GoogleEarth API access
!exists( $(QTDIR)/src/activeqt/Makefile ) {
message( Making QAx (ONE TIME) )
system( cd $$(QTDIR)\\src\\activeqt && $$(QTDIR)\\bin\\qmake.exe )
system( cd $$(QTDIR)\\src\\activeqt\\container && $$(QTDIR)\\bin\\qmake.exe )
system( cd $$(QTDIR)\\src\\activeqt\\control && $$(QTDIR)\\bin\\qmake.exe )
}
}
#################################################################
# EXTERNAL LIBRARY CONFIGURATION
# EIGEN matrix library (header-only)
INCLUDEPATH += libs/eigen
# OPMapControl library (from OpenPilot)
include(libs/utils/utils_external.pri)
include(libs/opmapcontrol/opmapcontrol_external.pri)
DEPENDPATH += \
libs/utils \
libs/utils/src \
libs/opmapcontrol \
libs/opmapcontrol/src \
libs/opmapcontrol/src/mapwidget
INCLUDEPATH += \
libs/utils \
libs \
libs/opmapcontrol
# If the user config file exists, it will be included.
# if the variable MAVLINK_CONF contains the name of an
# additional project, QGroundControl includes the support
# of custom MAVLink messages of this project. It will also
# create a QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use
# within the actual code.
exists(user_config.pri) {
include(user_config.pri)
message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF)
message("------------------------------------------------------------------------")
}
INCLUDEPATH += $$MAVLINKPATH
isEmpty(MAVLINK_CONF) {
INCLUDEPATH += $$MAVLINKPATH/common
} else {
INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF
#DEFINES += 'MAVLINK_CONF="$${MAVLINK_CONF}.h"'
DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF))
}
# Include general settings for QGroundControl
# necessary as last include to override any non-acceptable settings
# done by the plugins above
include(qgroundcontrol.pri)
# Include MAVLink generator
# has been deprecated
DEPENDPATH += \
src/apps/mavlinkgen
INCLUDEPATH += \
src/apps/mavlinkgen \
src/apps/mavlinkgen/ui \
src/apps/mavlinkgen/generator
include(src/apps/mavlinkgen/mavlinkgen.pri)
# Include QWT plotting library
include(libs/qwt/qwt.pri)
DEPENDPATH += . \
plugins \
libs/thirdParty/qserialport/include \
libs/thirdParty/qserialport/include/QtSerialPort \
libs/thirdParty/qserialport \
libs/qextserialport
INCLUDEPATH += . \
libs/thirdParty/qserialport/include \
libs/thirdParty/qserialport/include/QtSerialPort \
libs/thirdParty/qserialport/src \
libs/qextserialport
# Include serial port library (QSerial)
include(qserialport.pri)
# Serial port detection (ripped-off from qextserialport library)
macx|macx-g++|macx-g++42::SOURCES += libs/qextserialport/qextserialenumerator_osx.cpp
linux-g++::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
linux-g++-64::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
win32::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
win32-msvc2008|win32-msvc2010::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
# Input
FORMS += src/ui/MainWindow.ui \
src/ui/CommSettings.ui \
src/ui/SerialSettings.ui \
src/ui/UASControl.ui \
src/ui/UASList.ui \
src/ui/UASInfo.ui \
src/ui/Linechart.ui \
src/ui/UASView.ui \
src/ui/ParameterInterface.ui \
src/ui/WaypointList.ui \
src/ui/ObjectDetectionView.ui \
src/ui/JoystickWidget.ui \
src/ui/DebugConsole.ui \
src/ui/HDDisplay.ui \
src/ui/MAVLinkSettingsWidget.ui \
src/ui/AudioOutputWidget.ui \
src/ui/QGCSensorSettingsWidget.ui \
src/ui/watchdog/WatchdogControl.ui \
src/ui/watchdog/WatchdogProcessView.ui \
src/ui/watchdog/WatchdogView.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/QMap3D.ui \
src/ui/QGCWebView.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui \
src/ui/map/QGCMapTool.ui \
src/ui/map/QGCMapToolBar.ui \
src/ui/QGCMAVLinkInspector.ui \
src/ui/WaypointViewOnlyView.ui \
src/ui/WaypointEditableView.ui \
src/ui/UnconnectedUASInfoWidget.ui \
src/ui/mavlink/QGCMAVLinkMessageSender.ui \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \
src/ui/QGCPluginHost.ui \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \
src/ui/mission/QGCMissionOther.ui \
src/ui/mission/QGCMissionNavWaypoint.ui \
src/ui/mission/QGCMissionDoJump.ui \
src/ui/mission/QGCMissionConditionDelay.ui \
src/ui/mission/QGCMissionNavLoiterUnlim.ui \
src/ui/mission/QGCMissionNavLoiterTurns.ui \
src/ui/mission/QGCMissionNavLoiterTime.ui \
src/ui/mission/QGCMissionNavReturnToLaunch.ui \
src/ui/mission/QGCMissionNavLand.ui \
src/ui/mission/QGCMissionNavTakeoff.ui \
src/ui/mission/QGCMissionNavSweep.ui \
src/ui/mission/QGCMissionDoStartSearch.ui \
src/ui/mission/QGCMissionDoFinishSearch.ui \
src/ui/QGCVehicleConfig.ui \
src/ui/QGCHilConfiguration.ui \
src/ui/QGCHilFlightGearConfiguration.ui \
src/ui/QGCHilXPlaneConfiguration.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
src/ui/uas \
src/ui/map \
src/uas \
src/comm \
include/ui \
src/input \
src/lib/qmapcontrol \
src/ui/mavlink \
src/ui/param \
src/ui/watchdog \
src/ui/map3D \
src/ui/mission \
src/ui/designer
HEADERS += src/MG.h \
src/QGCCore.h \
src/uas/UASInterface.h \
src/uas/UAS.h \
src/uas/UASManager.h \
src/comm/LinkManager.h \
src/comm/LinkInterface.h \
src/comm/SerialLinkInterface.h \
src/comm/SerialLink.h \
src/comm/ProtocolInterface.h \
src/comm/MAVLinkProtocol.h \
src/comm/QGCFlightGearLink.h \
src/comm/QGCXPlaneLink.h \
src/ui/CommConfigurationWindow.h \
src/ui/SerialConfigurationWindow.h \
src/ui/MainWindow.h \
src/ui/uas/UASControlWidget.h \
src/ui/uas/UASListWidget.h \
src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \
src/configuration.h \
src/ui/uas/UASView.h \
src/ui/CameraView.h \
src/comm/MAVLinkSimulationLink.h \
src/comm/UDPLink.h \
src/ui/ParameterInterface.h \
src/ui/WaypointList.h \
src/Waypoint.h \
src/ui/ObjectDetectionView.h \
src/input/JoystickInput.h \
src/ui/JoystickWidget.h \
src/ui/DebugConsole.h \
src/ui/HDDisplay.h \
src/ui/MAVLinkSettingsWidget.h \
src/ui/AudioOutputWidget.h \
src/GAudioOutput.h \
src/LogCompressor.h \
src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/uas/senseSoarMAV.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \
src/uas/UASWaypointManager.h \
src/ui/HSIDisplay.h \
src/QGC.h \
src/ui/QGCFirmwareUpdate.h \
src/ui/QGCPxImuFirmwareUpdate.h \
src/ui/QGCDataPlot2D.h \
src/ui/linechart/IncrementalPlot.h \
src/ui/QGCRemoteControlView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \
src/ui/map3D/QGCWebPage.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h \
src/ui/uas/UASControlParameters.h \
src/uas/QGCUASParamManager.h \
src/ui/map/QGCMapWidget.h \
src/ui/map/MAV2DIcon.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/QGCMapTool.h \
src/ui/map/QGCMapToolBar.h \
libs/qextserialport/qextserialenumerator.h \
src/QGCGeo.h \
src/ui/QGCToolBar.h \
src/ui/QGCMAVLinkInspector.h \
src/ui/MAVLinkDecoder.h \
src/ui/WaypointViewOnlyView.h \
src/ui/WaypointViewOnlyView.h \
src/ui/WaypointEditableView.h \
src/ui/UnconnectedUASInfoWidget.h \
src/ui/QGCRGBDView.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \
src/ui/mission/QGCMissionOther.h \
src/ui/mission/QGCMissionNavWaypoint.h \
src/ui/mission/QGCMissionDoJump.h \
src/ui/mission/QGCMissionConditionDelay.h \
src/ui/mission/QGCMissionNavLoiterUnlim.h \
src/ui/mission/QGCMissionNavLoiterTurns.h \
src/ui/mission/QGCMissionNavLoiterTime.h \
src/ui/mission/QGCMissionNavReturnToLaunch.h \
src/ui/mission/QGCMissionNavLand.h \
src/ui/mission/QGCMissionNavTakeoff.h \
src/ui/mission/QGCMissionNavSweep.h \
src/ui/mission/QGCMissionDoStartSearch.h \
src/ui/mission/QGCMissionDoFinishSearch.h \
src/ui/QGCVehicleConfig.h \
src/comm/QGCHilLink.h \
src/ui/QGCHilConfiguration.h \
src/ui/QGCHilFlightGearConfiguration.h \
src/ui/QGCHilXPlaneConfiguration.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/gpl.h \
src/ui/map3D/CameraParams.h \
src/ui/map3D/ViewParamWidget.h \
src/ui/map3D/SystemContainer.h \
src/ui/map3D/SystemViewParams.h \
src/ui/map3D/GlobalViewParams.h \
src/ui/map3D/SystemGroupNode.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/GCManipulator.h \
src/ui/map3D/ImageWindowGeode.h \
src/ui/map3D/PixhawkCheetahNode.h \
src/ui/map3D/Pixhawk3DWidget.h \
src/ui/map3D/Q3DWidgetFactory.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h \
src/ui/map3D/TerrainParamDialog.h \
src/ui/map3D/ImageryParamDialog.h
}
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including headers for Protocol Buffers")
# Enable only if protobuf is available
HEADERS += libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h \
src/ui/map3D/ObstacleGroupNode.h \
src/ui/map3D/GLOverlayGeode.h
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including headers for libfreenect")
# Enable only if libfreenect is available
HEADERS += src/input/Freenect.h
}
SOURCES += src/main.cc \
src/QGCCore.cc \
src/uas/UASManager.cc \
src/uas/UAS.cc \
src/comm/LinkManager.cc \
src/comm/LinkInterface.cpp \
src/comm/SerialLink.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/QGCFlightGearLink.cc \
src/comm/QGCXPlaneLink.cc \
src/ui/CommConfigurationWindow.cc \
src/ui/SerialConfigurationWindow.cc \
src/ui/MainWindow.cc \
src/ui/uas/UASControlWidget.cc \
src/ui/uas/UASListWidget.cc \
src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \
src/ui/uas/UASView.cc \
src/ui/CameraView.cc \
src/comm/MAVLinkSimulationLink.cc \
src/comm/UDPLink.cc \
src/ui/ParameterInterface.cc \
src/ui/WaypointList.cc \
src/Waypoint.cc \
src/ui/ObjectDetectionView.cc \
src/input/JoystickInput.cc \
src/ui/JoystickWidget.cc \
src/ui/DebugConsole.cc \
src/ui/HDDisplay.cc \
src/ui/MAVLinkSettingsWidget.cc \
src/ui/AudioOutputWidget.cc \
src/GAudioOutput.cc \
src/LogCompressor.cc \
src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/uas/senseSoarMAV.cpp \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \
src/uas/UASWaypointManager.cc \
src/ui/HSIDisplay.cc \
src/QGC.cc \
src/ui/QGCFirmwareUpdate.cc \
src/ui/QGCPxImuFirmwareUpdate.cc \
src/ui/QGCDataPlot2D.cc \
src/ui/linechart/IncrementalPlot.cc \
src/ui/QGCRemoteControlView.cc \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc \
src/ui/uas/UASControlParameters.cpp \
src/uas/QGCUASParamManager.cc \
src/ui/map/QGCMapWidget.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/QGCMapTool.cc \
src/ui/map/QGCMapToolBar.cc \
src/ui/QGCToolBar.cc \
src/ui/QGCMAVLinkInspector.cc \
src/ui/MAVLinkDecoder.cc \
src/ui/WaypointViewOnlyView.cc \
src/ui/WaypointEditableView.cc \
src/ui/UnconnectedUASInfoWidget.cc \
src/ui/QGCRGBDView.cc \
src/ui/mavlink/QGCMAVLinkMessageSender.cc \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \
src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \
src/ui/mission/QGCMissionOther.cc \
src/ui/mission/QGCMissionNavWaypoint.cc \
src/ui/mission/QGCMissionDoJump.cc \
src/ui/mission/QGCMissionConditionDelay.cc \
src/ui/mission/QGCMissionNavLoiterUnlim.cc \
src/ui/mission/QGCMissionNavLoiterTurns.cc \
src/ui/mission/QGCMissionNavLoiterTime.cc \
src/ui/mission/QGCMissionNavReturnToLaunch.cc \
src/ui/mission/QGCMissionNavLand.cc \
src/ui/mission/QGCMissionNavTakeoff.cc \
src/ui/mission/QGCMissionNavSweep.cc \
src/ui/mission/QGCMissionDoStartSearch.cc \
src/ui/mission/QGCMissionDoFinishSearch.cc \
src/ui/QGCVehicleConfig.cc \
src/ui/QGCHilConfiguration.cc \
src/ui/QGCHilFlightGearConfiguration.cc \
src/ui/QGCHilXPlaneConfiguration.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
# Enable OSG only if it has been found
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/gpl.cc \
src/ui/map3D/CameraParams.cc \
src/ui/map3D/ViewParamWidget.cc \
src/ui/map3D/SystemContainer.cc \
src/ui/map3D/SystemViewParams.cc \
src/ui/map3D/GlobalViewParams.cc \
src/ui/map3D/SystemGroupNode.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/ImageWindowGeode.cc \
src/ui/map3D/GCManipulator.cc \
src/ui/map3D/PixhawkCheetahNode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \
src/ui/map3D/Q3DWidgetFactory.cc \
src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/TextureCache.cc \
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc \
src/ui/map3D/ImageryParamDialog.cc
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
# Enable only if OpenSceneGraph is available
SOURCES +=
}
}
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including sources for Protocol Buffers")
# Enable only if protobuf is available
SOURCES += libs/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \
src/ui/map3D/ObstacleGroupNode.cc \
src/ui/map3D/GLOverlayGeode.cc
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including sources for libfreenect")
# Enable only if libfreenect is available
SOURCES += src/input/Freenect.cc
}
# Add icons and other resources
RESOURCES += qgroundcontrol.qrc
# Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Building support for Opal-RT")
LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi
INCLUDEPATH += src/lib/opalrt
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
FORMS += src/ui/OpalLinkSettings.ui
DEFINES += OPAL_RT
}
TRANSLATIONS += es-MX.ts \
en-US.ts
# xbee support
# libxbee only supported by linux and windows systems
win32-msvc2008|win32-msvc2010|linux {
HEADERS += src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h
SOURCES += src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp
DEFINES += XBEELINK
INCLUDEPATH += libs/thirdParty/libxbee
# TO DO: build library when it does not exist already
LIBS += -Llibs/thirdParty/libxbee/lib \
-llibxbee
}
# -------------------------------------------------
# QGroundControl - Micro Air Vehicle Groundstation
# Please see our website at <http://qgroundcontrol.org>
# Maintainer:
# Lorenz Meier <lm@inf.ethz.ch>
# (c) 2009-2011 QGroundControl Developers
# This file is part of the open groundstation project
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
# -------------------------------------------------
# Qt configuration
CONFIG += qt \
thread
QT += network \
opengl \
svg \
xml \
phonon \
webkit \
sql
TEMPLATE = app
TARGET = qgroundcontrol
BASEDIR = $${IN_PWD}
linux-g++|linux-g++-64{
debug {
TARGETDIR = $${OUT_PWD}/debug
BUILDDIR = $${OUT_PWD}/build-debug
}
release {
TARGETDIR = $${OUT_PWD}/release
BUILDDIR = $${OUT_PWD}/build-release
}
} else {
TARGETDIR = $${OUT_PWD}
BUILDDIR = $${OUT_PWD}/build
}
LANGUAGE = C++
OBJECTS_DIR = $${BUILDDIR}/obj
MOC_DIR = $${BUILDDIR}/moc
UI_DIR = $${BUILDDIR}/ui
RCC_DIR = $${BUILDDIR}/rcc
MAVLINK_CONF = "pixhawk"
MAVLINKPATH = $$BASEDIR/libs/mavlink/include/mavlink/v1.0
DEFINES += MAVLINK_NO_DATA
win32 {
QMAKE_INCDIR_QT = $$(QTDIR)/include
QMAKE_LIBDIR_QT = $$(QTDIR)/lib
QMAKE_UIC = "$$(QTDIR)/bin/uic.exe"
QMAKE_MOC = "$$(QTDIR)/bin/moc.exe"
QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe"
QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe"
# Build QAX for GoogleEarth API access
!exists( $(QTDIR)/src/activeqt/Makefile ) {
message( Making QAx (ONE TIME) )
system( cd $$(QTDIR)\\src\\activeqt && $$(QTDIR)\\bin\\qmake.exe )
system( cd $$(QTDIR)\\src\\activeqt\\container && $$(QTDIR)\\bin\\qmake.exe )
system( cd $$(QTDIR)\\src\\activeqt\\control && $$(QTDIR)\\bin\\qmake.exe )
}
}
#################################################################
# EXTERNAL LIBRARY CONFIGURATION
# EIGEN matrix library (header-only)
INCLUDEPATH += libs/eigen
# OPMapControl library (from OpenPilot)
include(libs/utils/utils_external.pri)
include(libs/opmapcontrol/opmapcontrol_external.pri)
DEPENDPATH += \
libs/utils \
libs/utils/src \
libs/opmapcontrol \
libs/opmapcontrol/src \
libs/opmapcontrol/src/mapwidget
INCLUDEPATH += \
libs/utils \
libs \
libs/opmapcontrol
# If the user config file exists, it will be included.
# if the variable MAVLINK_CONF contains the name of an
# additional project, QGroundControl includes the support
# of custom MAVLink messages of this project. It will also
# create a QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use
# within the actual code.
exists(user_config.pri) {
include(user_config.pri)
message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF)
message("------------------------------------------------------------------------")
}
INCLUDEPATH += $$MAVLINKPATH
isEmpty(MAVLINK_CONF) {
INCLUDEPATH += $$MAVLINKPATH/common
} else {
INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF
#DEFINES += 'MAVLINK_CONF="$${MAVLINK_CONF}.h"'
DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF))
}
# Include general settings for QGroundControl
# necessary as last include to override any non-acceptable settings
# done by the plugins above
include(qgroundcontrol.pri)
# Include MAVLink generator
# has been deprecated
DEPENDPATH += \
src/apps/mavlinkgen
INCLUDEPATH += \
src/apps/mavlinkgen \
src/apps/mavlinkgen/ui \
src/apps/mavlinkgen/generator
include(src/apps/mavlinkgen/mavlinkgen.pri)
# Include QWT plotting library
include(libs/qwt/qwt.pri)
DEPENDPATH += . \
plugins \
libs/thirdParty/qserialport/include \
libs/thirdParty/qserialport/include/QtSerialPort \
libs/thirdParty/qserialport \
libs/qextserialport
INCLUDEPATH += . \
libs/thirdParty/qserialport/include \
libs/thirdParty/qserialport/include/QtSerialPort \
libs/thirdParty/qserialport/src \
libs/qextserialport
# Include serial port library (QSerial)
include(qserialport.pri)
# Serial port detection (ripped-off from qextserialport library)
macx|macx-g++|macx-g++42::SOURCES += libs/qextserialport/qextserialenumerator_osx.cpp
linux-g++::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
linux-g++-64::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
win32::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
win32-msvc2008|win32-msvc2010::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
# Input
FORMS += src/ui/MainWindow.ui \
src/ui/CommSettings.ui \
src/ui/SerialSettings.ui \
src/ui/UASControl.ui \
src/ui/UASList.ui \
src/ui/UASInfo.ui \
src/ui/Linechart.ui \
src/ui/UASView.ui \
src/ui/ParameterInterface.ui \
src/ui/WaypointList.ui \
src/ui/ObjectDetectionView.ui \
src/ui/JoystickWidget.ui \
src/ui/DebugConsole.ui \
src/ui/HDDisplay.ui \
src/ui/MAVLinkSettingsWidget.ui \
src/ui/AudioOutputWidget.ui \
src/ui/QGCSensorSettingsWidget.ui \
src/ui/watchdog/WatchdogControl.ui \
src/ui/watchdog/WatchdogProcessView.ui \
src/ui/watchdog/WatchdogView.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/QMap3D.ui \
src/ui/QGCWebView.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui \
src/ui/map/QGCMapTool.ui \
src/ui/map/QGCMapToolBar.ui \
src/ui/QGCMAVLinkInspector.ui \
src/ui/WaypointViewOnlyView.ui \
src/ui/WaypointEditableView.ui \
src/ui/UnconnectedUASInfoWidget.ui \
src/ui/mavlink/QGCMAVLinkMessageSender.ui \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \
src/ui/QGCPluginHost.ui \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \
src/ui/mission/QGCMissionOther.ui \
src/ui/mission/QGCMissionNavWaypoint.ui \
src/ui/mission/QGCMissionDoJump.ui \
src/ui/mission/QGCMissionConditionDelay.ui \
src/ui/mission/QGCMissionNavLoiterUnlim.ui \
src/ui/mission/QGCMissionNavLoiterTurns.ui \
src/ui/mission/QGCMissionNavLoiterTime.ui \
src/ui/mission/QGCMissionNavReturnToLaunch.ui \
src/ui/mission/QGCMissionNavLand.ui \
src/ui/mission/QGCMissionNavTakeoff.ui \
src/ui/mission/QGCMissionNavSweep.ui \
src/ui/mission/QGCMissionDoStartSearch.ui \
src/ui/mission/QGCMissionDoFinishSearch.ui \
src/ui/QGCVehicleConfig.ui \
src/ui/QGCHilConfiguration.ui \
src/ui/QGCHilFlightGearConfiguration.ui \
src/ui/QGCHilXPlaneConfiguration.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
src/ui/uas \
src/ui/map \
src/uas \
src/comm \
include/ui \
src/input \
src/lib/qmapcontrol \
src/ui/mavlink \
src/ui/param \
src/ui/watchdog \
src/ui/map3D \
src/ui/mission \
src/ui/designer
HEADERS += src/MG.h \
src/QGCCore.h \
src/uas/UASInterface.h \
src/uas/UAS.h \
src/uas/UASManager.h \
src/comm/LinkManager.h \
src/comm/LinkInterface.h \
src/comm/SerialLinkInterface.h \
src/comm/SerialLink.h \
src/comm/ProtocolInterface.h \
src/comm/MAVLinkProtocol.h \
src/comm/QGCFlightGearLink.h \
src/comm/QGCXPlaneLink.h \
src/ui/CommConfigurationWindow.h \
src/ui/SerialConfigurationWindow.h \
src/ui/MainWindow.h \
src/ui/uas/UASControlWidget.h \
src/ui/uas/UASListWidget.h \
src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \
src/configuration.h \
src/ui/uas/UASView.h \
src/ui/CameraView.h \
src/comm/MAVLinkSimulationLink.h \
src/comm/UDPLink.h \
src/ui/ParameterInterface.h \
src/ui/WaypointList.h \
src/Waypoint.h \
src/ui/ObjectDetectionView.h \
src/input/JoystickInput.h \
src/ui/JoystickWidget.h \
src/ui/DebugConsole.h \
src/ui/HDDisplay.h \
src/ui/MAVLinkSettingsWidget.h \
src/ui/AudioOutputWidget.h \
src/GAudioOutput.h \
src/LogCompressor.h \
src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/uas/senseSoarMAV.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \
src/uas/UASWaypointManager.h \
src/ui/HSIDisplay.h \
src/QGC.h \
src/ui/QGCFirmwareUpdate.h \
src/ui/QGCPxImuFirmwareUpdate.h \
src/ui/QGCDataPlot2D.h \
src/ui/linechart/IncrementalPlot.h \
src/ui/QGCRemoteControlView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \
src/ui/map3D/QGCWebPage.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h \
src/ui/uas/UASControlParameters.h \
src/uas/QGCUASParamManager.h \
src/ui/map/QGCMapWidget.h \
src/ui/map/MAV2DIcon.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/QGCMapTool.h \
src/ui/map/QGCMapToolBar.h \
libs/qextserialport/qextserialenumerator.h \
src/QGCGeo.h \
src/ui/QGCToolBar.h \
src/ui/QGCMAVLinkInspector.h \
src/ui/MAVLinkDecoder.h \
src/ui/WaypointViewOnlyView.h \
src/ui/WaypointViewOnlyView.h \
src/ui/WaypointEditableView.h \
src/ui/UnconnectedUASInfoWidget.h \
src/ui/QGCRGBDView.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \
src/ui/mission/QGCMissionOther.h \
src/ui/mission/QGCMissionNavWaypoint.h \
src/ui/mission/QGCMissionDoJump.h \
src/ui/mission/QGCMissionConditionDelay.h \
src/ui/mission/QGCMissionNavLoiterUnlim.h \
src/ui/mission/QGCMissionNavLoiterTurns.h \
src/ui/mission/QGCMissionNavLoiterTime.h \
src/ui/mission/QGCMissionNavReturnToLaunch.h \
src/ui/mission/QGCMissionNavLand.h \
src/ui/mission/QGCMissionNavTakeoff.h \
src/ui/mission/QGCMissionNavSweep.h \
src/ui/mission/QGCMissionDoStartSearch.h \
src/ui/mission/QGCMissionDoFinishSearch.h \
src/ui/QGCVehicleConfig.h \
src/comm/QGCHilLink.h \
src/ui/QGCHilConfiguration.h \
src/ui/QGCHilFlightGearConfiguration.h \
src/ui/QGCHilXPlaneConfiguration.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/gpl.h \
src/ui/map3D/CameraParams.h \
src/ui/map3D/ViewParamWidget.h \
src/ui/map3D/SystemContainer.h \
src/ui/map3D/SystemViewParams.h \
src/ui/map3D/GlobalViewParams.h \
src/ui/map3D/SystemGroupNode.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/GCManipulator.h \
src/ui/map3D/ImageWindowGeode.h \
src/ui/map3D/PixhawkCheetahNode.h \
src/ui/map3D/Pixhawk3DWidget.h \
src/ui/map3D/Q3DWidgetFactory.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h \
src/ui/map3D/TerrainParamDialog.h \
src/ui/map3D/ImageryParamDialog.h
}
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including headers for Protocol Buffers")
# Enable only if protobuf is available
HEADERS += libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h \
src/ui/map3D/ObstacleGroupNode.h \
src/ui/map3D/GLOverlayGeode.h
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including headers for libfreenect")
# Enable only if libfreenect is available
HEADERS += src/input/Freenect.h
}
SOURCES += src/main.cc \
src/QGCCore.cc \
src/uas/UASManager.cc \
src/uas/UAS.cc \
src/comm/LinkManager.cc \
src/comm/LinkInterface.cpp \
src/comm/SerialLink.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/QGCFlightGearLink.cc \
src/comm/QGCXPlaneLink.cc \
src/ui/CommConfigurationWindow.cc \
src/ui/SerialConfigurationWindow.cc \
src/ui/MainWindow.cc \
src/ui/uas/UASControlWidget.cc \
src/ui/uas/UASListWidget.cc \
src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \
src/ui/uas/UASView.cc \
src/ui/CameraView.cc \
src/comm/MAVLinkSimulationLink.cc \
src/comm/UDPLink.cc \
src/ui/ParameterInterface.cc \
src/ui/WaypointList.cc \
src/Waypoint.cc \
src/ui/ObjectDetectionView.cc \
src/input/JoystickInput.cc \
src/ui/JoystickWidget.cc \
src/ui/DebugConsole.cc \
src/ui/HDDisplay.cc \
src/ui/MAVLinkSettingsWidget.cc \
src/ui/AudioOutputWidget.cc \
src/GAudioOutput.cc \
src/LogCompressor.cc \
src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/uas/senseSoarMAV.cpp \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \
src/uas/UASWaypointManager.cc \
src/ui/HSIDisplay.cc \
src/QGC.cc \
src/ui/QGCFirmwareUpdate.cc \
src/ui/QGCPxImuFirmwareUpdate.cc \
src/ui/QGCDataPlot2D.cc \
src/ui/linechart/IncrementalPlot.cc \
src/ui/QGCRemoteControlView.cc \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc \
src/ui/uas/UASControlParameters.cpp \
src/uas/QGCUASParamManager.cc \
src/ui/map/QGCMapWidget.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/QGCMapTool.cc \
src/ui/map/QGCMapToolBar.cc \
src/ui/QGCToolBar.cc \
src/ui/QGCMAVLinkInspector.cc \
src/ui/MAVLinkDecoder.cc \
src/ui/WaypointViewOnlyView.cc \
src/ui/WaypointEditableView.cc \
src/ui/UnconnectedUASInfoWidget.cc \
src/ui/QGCRGBDView.cc \
src/ui/mavlink/QGCMAVLinkMessageSender.cc \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \
src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \
src/ui/mission/QGCMissionOther.cc \
src/ui/mission/QGCMissionNavWaypoint.cc \
src/ui/mission/QGCMissionDoJump.cc \
src/ui/mission/QGCMissionConditionDelay.cc \
src/ui/mission/QGCMissionNavLoiterUnlim.cc \
src/ui/mission/QGCMissionNavLoiterTurns.cc \
src/ui/mission/QGCMissionNavLoiterTime.cc \
src/ui/mission/QGCMissionNavReturnToLaunch.cc \
src/ui/mission/QGCMissionNavLand.cc \
src/ui/mission/QGCMissionNavTakeoff.cc \
src/ui/mission/QGCMissionNavSweep.cc \
src/ui/mission/QGCMissionDoStartSearch.cc \
src/ui/mission/QGCMissionDoFinishSearch.cc \
src/ui/QGCVehicleConfig.cc \
src/ui/QGCHilConfiguration.cc \
src/ui/QGCHilFlightGearConfiguration.cc \
src/ui/QGCHilXPlaneConfiguration.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
# Enable OSG only if it has been found
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/gpl.cc \
src/ui/map3D/CameraParams.cc \
src/ui/map3D/ViewParamWidget.cc \
src/ui/map3D/SystemContainer.cc \
src/ui/map3D/SystemViewParams.cc \
src/ui/map3D/GlobalViewParams.cc \
src/ui/map3D/SystemGroupNode.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/ImageWindowGeode.cc \
src/ui/map3D/GCManipulator.cc \
src/ui/map3D/PixhawkCheetahNode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \
src/ui/map3D/Q3DWidgetFactory.cc \
src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/TextureCache.cc \
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc \
src/ui/map3D/ImageryParamDialog.cc
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
# Enable only if OpenSceneGraph is available
SOURCES +=
}
}
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including sources for Protocol Buffers")
# Enable only if protobuf is available
SOURCES += libs/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \
src/ui/map3D/ObstacleGroupNode.cc \
src/ui/map3D/GLOverlayGeode.cc
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including sources for libfreenect")
# Enable only if libfreenect is available
SOURCES += src/input/Freenect.cc
}
# Add icons and other resources
RESOURCES += qgroundcontrol.qrc
# Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Building support for Opal-RT")
LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi
INCLUDEPATH += src/lib/opalrt
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
FORMS += src/ui/OpalLinkSettings.ui
DEFINES += OPAL_RT
}
TRANSLATIONS += es-MX.ts \
en-US.ts
# xbee support
# libxbee only supported by linux and windows systems
win32-msvc2008|win32-msvc2010|linux {
HEADERS += src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h
SOURCES += src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp
DEFINES += XBEELINK
INCLUDEPATH += libs/thirdParty/libxbee
# TO DO: build library when it does not exist already
LIBS += -Llibs/thirdParty/libxbee/lib \
-llibxbee
}
###################################################################
#### --- 3DConnexion 3d Mice support (e.g. spacenavigator) --- ####
###################################################################
# xdrvlib only supported by linux (theoretical all X11) systems
# You have to install the official 3DxWare driver for linux to use 3D mouse support on linux systems!
linux-g++|linux-g++-64{
exists(/usr/local/lib/libxdrvlib.so){
message("Including support for Magellan 3DxWare for linux system.")
SOURCES += src/input/Mouse6dofInput.cpp
HEADERS += src/input/Mouse6dofInput.h
LIBS += -L/usr/local/lib/ -lxdrvlib
INCLUDEPATH *= /usr/local/include
DEFINES += MOUSE_ENABLED_LINUX \
ParameterCheck # Hack: Has to be defined for magellan usage
}
}
# Support for Windows systems
# You have to install the official 3DxWare driver for Windows to use the 3D mouse support on Windows systems!
win32-msvc2008|win32-msvc2010 {
message("Including support for 3DxWare for Windows system.")
SOURCES += libs/thirdParty/3DMouse/win/MouseParameters.cpp \
libs/thirdParty/3DMouse/win/Mouse3DInput.cpp \
src/input/Mouse6dofInput.cpp
HEADERS += libs/thirdParty/3DMouse/win/I3dMouseParams.h \
libs/thirdParty/3DMouse/win/MouseParameters.h \
libs/thirdParty/3DMouse/win/Mouse3DInput.h \
src/input/Mouse6dofInput.h
INCLUDEPATH += libs/thirdParty/3DMouse/win
DEFINES += MOUSE_ENABLED_WIN
}
/**
* @file
* @brief 3dConnexion 3dMouse interface for QGroundControl
*
* @author Matthias Krebs <makrebs@student.ethz.ch>
*
*/
#include "Mouse6dofInput.h"
#include "UAS.h"
#include "UASManager.h"
#include "QMessageBox"
#ifdef MOUSE_ENABLED_LINUX
#include <QX11Info>
#include <X11/Xlib.h>
#ifdef Success
#undef Success // Eigen library doesn't work if Success is defined
#endif //Success
extern "C"
{
#include "xdrvlib.h"
}
#endif // MOUSE_ENABLED_LINUX
#ifdef MOUSE_ENABLED_WIN
Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) :
mouse3DMax(0.075), // TODO: check maximum value fot plugged device
uas(NULL),
done(false),
mouseActive(false),
translationActive(true),
rotationActive(true),
xValue(0.0),
yValue(0.0),
zValue(0.0),
aValue(0.0),
bValue(0.0),
cValue(0.0)
{
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
// Connect 3DxWare SDK MotionEvent
connect(mouseInput, SIGNAL(Move3d(std::vector<float>&)), this, SLOT(motion3DMouse(std::vector<float>&)));
connect(mouseInput, SIGNAL(On3dmouseKeyDown(int)), this, SLOT(button3DMouseDown(int)));
//connect(mouseInput, SIGNAL(On3dmouseKeyUp(int)), this, SLOT(FUNCTION(int)));
}
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
Mouse6dofInput::Mouse6dofInput(QWidget* parent) :
mouse3DMax(350.0), // TODO: check maximum value fot plugged device
uas(NULL),
done(false),
mouseActive(false),
translationActive(true),
rotationActive(true),
xValue(0.0),
yValue(0.0),
zValue(0.0),
aValue(0.0),
bValue(0.0),
cValue(0.0)
{
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
if (!mouseActive)
{
// // man visudo --> then you can omit giving password (success not guarantied..)
// qDebug() << "Starting 3DxWare Daemon for 3dConnexion 3dMouse";
// QString processProgramm = "gksudo";
// QStringList processArguments;
// processArguments << "/etc/3DxWare/daemon/3dxsrv -d usb";
// process3dxDaemon = new QProcess();
// process3dxDaemon->start(processProgramm, processArguments);
// // process3dxDaemon->waitForFinished();
// // {
// // qDebug() << "... continuing without 3DxWare. May not be initialized properly!";
// // qDebug() << "Try in terminal as user root:" << processArguments.last();
// // }
Display *display = QX11Info::display();
if(!display)
{
qDebug() << "Cannot open display!" << endl;
}
if ( !MagellanInit( display, parent->winId() ) )
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Information);
msgBox.setText(tr("No 3DxWare driver is running."));
msgBox.setInformativeText(tr("Enter in Terminal 'sudo /etc/3DxWare/daemon/3dxsrv -d usb' and then restart QGroundControl."));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
qDebug() << "No 3DxWare driver is running!";
return;
}
else
{
qDebug() << "Initialized 3dMouse";
mouseActive = true;
}
}
else
{
qDebug() << "3dMouse already initialized..";
}
}
#endif //MOUSE_ENABLED_LINUX
Mouse6dofInput::~Mouse6dofInput()
{
done = true;
}
void Mouse6dofInput::setActiveUAS(UASInterface* uas)
{
// Only connect / disconnect is the UAS is of a controllable UAS class
UAS* tmp = 0;
if (this->uas)
{
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp)
{
disconnect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), tmp, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
// Todo: disconnect button mapping
}
}
this->uas = uas;
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp) {
connect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), tmp, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
// Todo: connect button mapping
}
if (!isRunning())
{
start();
}
}
void Mouse6dofInput::init()
{
// Make sure active UAS is set
setActiveUAS(UASManager::instance()->getActiveUAS());
}
void Mouse6dofInput::run()
{
init();
forever
{
if (done)
{
done = false;
exit();
}
if (mouseActive)
{
// Bound x value
if (xValue > 1.0) xValue = 1.0;
if (xValue < -1.0) xValue = -1.0;
// Bound x value
if (yValue > 1.0) yValue = 1.0;
if (yValue < -1.0) yValue = -1.0;
// Bound x value
if (zValue > 1.0) zValue = 1.0;
if (zValue < -1.0) zValue = -1.0;
// Bound x value
if (aValue > 1.0) aValue = 1.0;
if (aValue < -1.0) aValue = -1.0;
// Bound x value
if (bValue > 1.0) bValue = 1.0;
if (bValue < -1.0) bValue = -1.0;
// Bound x value
if (cValue > 1.0) cValue = 1.0;
if (cValue < -1.0) cValue = -1.0;
emit mouse6dofChanged(xValue, yValue, zValue, aValue, bValue, cValue);
}
// Sleep, update rate of 3d mouse is approx. 50 Hz (1000 ms / 50 = 20 ms)
QGC::SLEEP::msleep(20);
}
}
#ifdef MOUSE_ENABLED_WIN
void Mouse6dofInput::motion3DMouse(std::vector<float> &motionData)
{
if (motionData.size() < 6) return;
mouseActive = true;
if (translationActive)
{
xValue = (double)1.0e2f*motionData[ 1 ] / mouse3DMax;
yValue = (double)1.0e2f*motionData[ 0 ] / mouse3DMax;
zValue = (double)1.0e2f*motionData[ 2 ] / mouse3DMax;
}else{
xValue = 0;
yValue = 0;
zValue = 0;
}
if (rotationActive)
{
aValue = (double)1.0e2f*motionData[ 4 ] / mouse3DMax;
bValue = (double)1.0e2f*motionData[ 3 ] / mouse3DMax;
cValue = (double)1.0e2f*motionData[ 5 ] / mouse3DMax;
}else{
aValue = 0;
bValue = 0;
cValue = 0;
}
//qDebug() << "NEW 3D MOUSE VALUES -- X" << xValue << " -- Y" << yValue << " -- Z" << zValue << " -- A" << aValue << " -- B" << bValue << " -- C" << cValue;
}
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_WIN
void Mouse6dofInput::button3DMouseDown(int button)
{
switch(button)
{
case 1:
{
rotationActive = !rotationActive;
emit mouseRotationActiveChanged(rotationActive);
qDebug() << "Changed 3DMouse Rotation to " << (bool)rotationActive;
break;
}
case 2:
{
translationActive = !translationActive;
emit mouseTranslationActiveChanged(translationActive);
qDebug() << "Changed 3DMouse Translation to" << (bool)translationActive;
break;
}
default:
break;
}
}
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
void Mouse6dofInput::handleX11Event(XEvent *event)
{
//qDebug("XEvent occured...");
if (!mouseActive)
{
qDebug() << "3dMouse not initialized. Cancelled handling X11event for 3dMouse";
return;
}
MagellanFloatEvent MagellanEvent;
Display *display = QX11Info::display();
if(!display)
{
qDebug() << "Cannot open display!" << endl;
}
switch (event->type)
{
case ClientMessage:
switch( MagellanTranslateEvent( display, event, &MagellanEvent, 1.0, 1.0 ) )
{
case MagellanInputMotionEvent :
MagellanRemoveMotionEvents( display );
for (int i = 0; i < 6; i++) { // Saturation
MagellanEvent.MagellanData[i] = (abs(MagellanEvent.MagellanData[i]) < mouse3DMax) ? MagellanEvent.MagellanData[i] : (mouse3DMax*MagellanEvent.MagellanData[i]/abs(MagellanEvent.MagellanData[i]));
}
// Check whether translational motions are enabled
if (translationActive)
{
xValue = MagellanEvent.MagellanData[ MagellanZ ] / mouse3DMax;
yValue = MagellanEvent.MagellanData[ MagellanX ] / mouse3DMax;
zValue = - MagellanEvent.MagellanData[ MagellanY ] / mouse3DMax;
}else{
xValue = 0;
yValue = 0;
zValue = 0;
}
// Check whether rotational motions are enabled
if (rotationActive)
{
aValue = MagellanEvent.MagellanData[ MagellanC ] / mouse3DMax;
bValue = MagellanEvent.MagellanData[ MagellanA ] / mouse3DMax;
cValue = - MagellanEvent.MagellanData[ MagellanB ] / mouse3DMax;
}else{
aValue = 0;
bValue = 0;
cValue = 0;
}
//qDebug() << "NEW 3D MOUSE VALUES -- X" << xValue << " -- Y" << yValue << " -- Z" << zValue << " -- A" << aValue << " -- B" << bValue << " -- C" << cValue;
break;
case MagellanInputButtonPressEvent :
qDebug() << "MagellanInputButtonPressEvent called with button " << MagellanEvent.MagellanButton;
switch (MagellanEvent.MagellanButton)
{
case 1:
{
rotationActive = !rotationActive;
emit mouseRotationActiveChanged(rotationActive);
qDebug() << "Changed 3DMouse Rotation to " << (bool)rotationActive;
break;
}
case 2:
{
translationActive = !translationActive;
emit mouseTranslationActiveChanged(translationActive);
qDebug() << "Changed 3DMouse Translation to" << (bool)translationActive;
break;
}
default:
break;
}
default:
break;
}
}
}
#endif //MOUSE_ENABLED_LINUX
/**
* @file
* @brief Definition of 3dConnexion 3dMouse interface for QGroundControl
*
* @author Matthias Krebs <makrebs@student.ethz.ch>
*
*/
#ifndef MOUSE6DOFINPUT_H
#define MOUSE6DOFINPUT_H
#include <QThread>
#ifdef MOUSE_ENABLED_WIN
#include "Mouse3DInput.h"
#endif //MOUSE_ENABLED_WIN
#include "UASInterface.h"
class Mouse6dofInput : public QThread
{
Q_OBJECT
public:
#ifdef MOUSE_ENABLED_WIN
Mouse6dofInput(Mouse3DInput* mouseInput);
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
Mouse6dofInput(QWidget* parent);
#endif //MOUSE_ENABLED_LINUX
~Mouse6dofInput();
void run();
const double mouse3DMax;
protected:
void init();
UASInterface* uas;
bool done;
bool mouseActive;
bool translationActive;
bool rotationActive;
double xValue;
double yValue;
double zValue;
double aValue;
double bValue;
double cValue;
signals:
/**
* @brief Input of the 3d mouse has changed
*
* @param x Input x direction, range [-1, 1]
* @param y Input y direction, range [-1, 1]
* @param z Input z direction, range [-1, 1]
* @param a Input x rotation, range [-1, 1]
* @param b Input y rotation, range [-1, 1]
* @param c Input z rotation, range [-1, 1]
*/
void mouse6dofChanged(double x, double y, double z, double a, double b, double c);
/**
* @brief Activity of translational 3DMouse inputs changed
* @param translationEnable, true: translational inputs active; false: translational inputs ingored
*/
void mouseTranslationActiveChanged(bool translationEnable);
/**
* @brief Activity of rotational 3DMouse inputs changed
* @param rotationEnable, true: rotational inputs active; false: rotational inputs ingored
*/
void mouseRotationActiveChanged(bool rotationEnable);
public slots:
void setActiveUAS(UASInterface* uas);
#ifdef MOUSE_ENABLED_WIN
/** @brief Get a motion input from 3DMouse */
void motion3DMouse(std::vector<float> &motionData);
/** @brief Get a button input from 3DMouse */
void button3DMouseDown(int button);
#endif //MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
/** @brief Get an XEvent to check it for an 3DMouse event (motion or button) */
void handleX11Event(XEvent* event);
#endif //MOUSE_ENABLED_LINUX
};
#endif // MOUSE6DOFINPUT_H
This source diff could not be displayed because it is too large. You can view the blob instead.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of Unmanned Aerial Vehicle object
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _UAS_H_
#define _UAS_H_
#include "UASInterface.h"
#include <MAVLinkProtocol.h>
#include <QVector3D>
#include "QGCMAVLink.h"
#include "QGCHilLink.h"
#include "QGCFlightGearLink.h"
#include "QGCXPlaneLink.h"
/**
* @brief A generic MAVLINK-connected MAV/UAV
*
* This class represents one vehicle. It can be used like the real vehicle, e.g. a call to halt()
* will automatically send the appropriate messages to the vehicle. The vehicle state will also be
* automatically updated by the comm architecture, so when writing code to e.g. control the vehicle
* no knowledge of the communication infrastructure is needed.
*/
class UAS : public UASInterface
{
Q_OBJECT
public:
UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS();
enum BatteryType
{
NICD = 0,
NIMH = 1,
LIION = 2,
LIPOLY = 3,
LIFE = 4,
AGZN = 5
}; ///< The type of battery used
static const int lipoFull = 4.2f; ///< 100% charged voltage
static const int lipoEmpty = 3.5f; ///< Discharged voltage
/* MANAGEMENT */
/** @brief The name of the robot */
QString getUASName(void) const;
/** @brief Get short state */
const QString& getShortState() const;
/** @brief Get short mode */
const QString& getShortMode() const;
/** @brief Translate from mode id to text */
static QString getShortModeTextFor(int id);
/** @brief Translate from mode id to audio text */
static QString getAudioModeTextFor(int id);
/** @brief Get the unique system id */
int getUASID() const;
/** @brief Get the airframe */
int getAirframe() const
{
return airframe;
}
/** @brief Get the components */
QMap<int, QString> getComponents();
/** @brief The time interval the robot is switched on */
quint64 getUptime() const;
/** @brief Get the status flag for the communication */
int getCommunicationStatus() const;
/** @brief Add one measurement and get low-passed voltage */
float filterVoltage(float value) const;
/** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks();
double getLocalX() const
{
return localX;
}
double getLocalY() const
{
return localY;
}
double getLocalZ() const
{
return localZ;
}
double getLatitude() const
{
return latitude;
}
double getLongitude() const
{
return longitude;
}
double getAltitude() const
{
return altitude;
}
virtual bool localPositionKnown() const
{
return isLocalPositionKnown;
}
virtual bool globalPositionKnown() const
{
return isGlobalPositionKnown;
}
double getRoll() const
{
return roll;
}
double getPitch() const
{
return pitch;
}
double getYaw() const
{
return yaw;
}
bool getSelected() const;
QVector3D getNedPosGlobalOffset() const
{
return nedPosGlobalOffset;
}
QVector3D getNedAttGlobalOffset() const
{
return nedAttGlobalOffset;
}
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay getOverlay()
{
QMutexLocker locker(&overlayMutex);
return overlay;
}
px::GLOverlay getOverlay(qreal& receivedTimestamp)
{
receivedTimestamp = receivedOverlayTimestamp;
QMutexLocker locker(&overlayMutex);
return overlay;
}
px::ObstacleList getObstacleList() {
QMutexLocker locker(&obstacleListMutex);
return obstacleList;
}
px::ObstacleList getObstacleList(qreal& receivedTimestamp) {
receivedTimestamp = receivedObstacleListTimestamp;
QMutexLocker locker(&obstacleListMutex);
return obstacleList;
}
px::Path getPath() {
QMutexLocker locker(&pathMutex);
return path;
}
px::Path getPath(qreal& receivedTimestamp) {
receivedTimestamp = receivedPathTimestamp;
QMutexLocker locker(&pathMutex);
return path;
}
px::PointCloudXYZRGB getPointCloud() {
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
receivedTimestamp = receivedPointCloudTimestamp;
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::RGBDImage getRGBDImage() {
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
receivedTimestamp = receivedRGBDImageTimestamp;
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
#endif
friend class UASWaypointManager;
protected: //COMMENTS FOR TEST UNIT
int uasId; ///< Unique system ID
unsigned char type; ///< UAS type (from type enum)
quint64 startTime; ///< The time the UAS was switched on
CommStatus commStatus; ///< Communication status
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
BatteryType batteryType; ///< The battery type
int cells; ///< Number of cells
UASWaypointManager waypointManager;
QList<double> actuatorValues;
QList<QString> actuatorNames;
QList<double> motorValues;
QList<QString> motorNames;
QMap<int, QString> components; ///< IDs and names of all detected onboard components
double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons
double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons
// Battery stats
float fullVoltage; ///< Voltage of the fully charged battery (100%)
float emptyVoltage; ///< Voltage of the empty battery (0%)
float startVoltage; ///< Voltage at system start
float tickVoltage; ///< Voltage where 0.1 V ticks are told
float lastTickVoltageValue; ///< The last voltage where a tick was announced
float tickLowpassVoltage; ///< Lowpass-filtered voltage for the tick announcement
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
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
uint32_t navMode; ///< The current navigation mode of the MAV
quint64 onboardTimeOffset;
bool controlRollManual; ///< status flag, true if roll is controlled manually
bool controlPitchManual; ///< status flag, true if pitch is controlled manually
bool controlYawManual; ///< status flag, true if yaw is controlled manually
bool controlThrustManual; ///< status flag, true if thrust is controlled manually
double manualRollAngle; ///< Roll angle set by human pilot (radians)
double manualPitchAngle; ///< Pitch angle set by human pilot (radians)
double manualYawAngle; ///< Yaw angle set by human pilot (radians)
double manualThrust; ///< Thrust set by human pilot (radians)
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
bool lowBattAlarm; ///< Switch if battery is low
bool positionLock; ///< Status if position information is available or not
double localX;
double localY;
double localZ;
double latitude;
double longitude;
double altitude;
double speedX; ///< True speed in X axis
double speedY; ///< True speed in Y axis
double speedZ; ///< True speed in Z axis
double roll;
double pitch;
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; ///< Quality of the transmitted image (percentage)
int imageType; ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
int imageWidth; ///< Width of the image stream
int imageHeight; ///< Width of the image stream
QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream
QImage image; ///< Image data of last completely transmitted image
quint64 imageStart;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay overlay;
QMutex overlayMutex;
qreal receivedOverlayTimestamp;
px::ObstacleList obstacleList;
QMutex obstacleListMutex;
qreal receivedObstacleListTimestamp;
px::Path path;
QMutex pathMutex;
qreal receivedPathTimestamp;
px::PointCloudXYZRGB pointCloud;
QMutex pointCloudMutex;
qreal receivedPointCloudTimestamp;
px::RGBDImage rgbdImage;
QMutex rgbdImageMutex;
qreal receivedRGBDImageTimestamp;
#endif
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
QGCUASParamManager* paramManager; ///< Parameter manager class
QString shortStateText; ///< Short textual state description
QString shortModeText; ///< Short textual mode description
bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV
quint64 lastAttitude; ///< Timestamp of last attitude measurement
QGCHilLink* simulation; ///< Hardware in the loop simulation link
bool isLocalPositionKnown; ///< If the local position has been received for this MAV
bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
bool systemIsArmed; ///< If the system is armed
QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
public:
/** @brief Set the current battery type */
void setBattery(BatteryType type, int cells);
/** @brief Estimate how much flight time is remaining */
int calculateTimeRemaining();
/** @brief Get the current charge level */
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();
/** @brief Check if vehicle is armed */
bool isArmed() const { return systemIsArmed; }
UASWaypointManager* getWaypointManager() {
return &waypointManager;
}
/** @brief Get reference to the param manager **/
QGCUASParamManager* getParamManager() const {
return paramManager;
}
/** @brief Get the HIL simulation */
QGCHilLink* getHILSimulation() const {
return simulation;
}
// TODO Will be removed
/** @brief Set reference to the param manager **/
void setParamManager(QGCUASParamManager* manager) {
paramManager = manager;
}
int getSystemType();
QString getSystemTypeName()
{
switch(type)
{
case MAV_TYPE_GENERIC:
return "GENERIC";
break;
case MAV_TYPE_FIXED_WING:
return "FIXED_WING";
break;
case MAV_TYPE_QUADROTOR:
return "QUADROTOR";
break;
case MAV_TYPE_COAXIAL:
return "COAXIAL";
break;
case MAV_TYPE_HELICOPTER:
return "HELICOPTER";
break;
case MAV_TYPE_ANTENNA_TRACKER:
return "ANTENNA_TRACKER";
break;
case MAV_TYPE_GCS:
return "GCS";
break;
case MAV_TYPE_AIRSHIP:
return "AIRSHIP";
break;
case MAV_TYPE_FREE_BALLOON:
return "FREE_BALLOON";
break;
case MAV_TYPE_ROCKET:
return "ROCKET";
break;
case MAV_TYPE_GROUND_ROVER:
return "GROUND_ROVER";
break;
case MAV_TYPE_SURFACE_BOAT:
return "BOAT";
break;
case MAV_TYPE_SUBMARINE:
return "SUBMARINE";
break;
case MAV_TYPE_HEXAROTOR:
return "HEXAROTOR";
break;
case MAV_TYPE_OCTOROTOR:
return "OCTOROTOR";
break;
case MAV_TYPE_TRICOPTER:
return "TRICOPTER";
break;
case MAV_TYPE_FLAPPING_WING:
return "FLAPPING_WING";
break;
default:
return "";
break;
}
}
QImage getImage();
void requestImage();
int getAutopilotType(){
return autopilot;
}
QString getAutopilotTypeName()
{
switch (autopilot)
{
case MAV_AUTOPILOT_GENERIC:
return "GENERIC";
break;
case MAV_AUTOPILOT_PIXHAWK:
return "PIXHAWK";
break;
case MAV_AUTOPILOT_SLUGS:
return "SLUGS";
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
return "ARDUPILOTMEGA";
break;
case MAV_AUTOPILOT_OPENPILOT:
return "OPENPILOT";
break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
return "GENERIC_WAYPOINTS_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
return "GENERIC_MISSION_NAVIGATION_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_MISSION_FULL:
return "GENERIC_MISSION_FULL";
break;
case MAV_AUTOPILOT_INVALID:
return "NO AP";
break;
case MAV_AUTOPILOT_PPZ:
return "PPZ";
break;
case MAV_AUTOPILOT_UDB:
return "UDB";
break;
case MAV_AUTOPILOT_FP:
return "FP";
break;
case MAV_AUTOPILOT_PX4:
return "PX4";
break;
default:
return "";
break;
}
}
public slots:
/** @brief Set the autopilot type */
void setAutopilotType(int apType)
{
autopilot = apType;
emit systemSpecsChanged(uasId);
}
/** @brief Set the type of airframe */
void setSystemType(int systemType);
/** @brief Set the specific airframe type */
void setAirframe(int airframe)
{
if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM))
{
this->airframe = airframe;
emit systemSpecsChanged(uasId);
}
}
/** @brief Set a new name **/
void setUASName(const QString& name);
/** @brief Executes a command **/
void executeCommand(MAV_CMD command);
/** @brief Executes a command with 7 params */
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
/** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */
QString getBatterySpecs();
/** @brief Launches the system **/
void launch();
/** @brief Write this waypoint to the list of waypoints */
//void setWaypoint(Waypoint* wp); FIXME tbd
/** @brief Set currently active waypoint */
//void setWaypointActive(int id); FIXME tbd
/** @brief Order the robot to return home **/
void home();
/** @brief Order the robot to land **/
void land();
void halt();
void go();
/** @brief Enable / disable HIL */
void enableHilFlightGear(bool enable, QString options);
void enableHilXPlane(bool enable);
/** @brief Send the full HIL state to the MAV */
void sendHilState( uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc);
/** @brief Places the UAV in Hardware-in-the-Loop simulation status **/
void startHil();
/** @brief Stops the UAV's Hardware-in-the-Loop simulation status **/
void stopHil();
/** @brief Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
void emergencySTOP();
/** @brief Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
bool emergencyKILL();
/** @brief Shut the system cleanly down. Will shut down any onboard computers **/
void shutdown();
/** @brief Set the target position for the robot to navigate to. */
void setTargetPosition(float x, float y, float z, float yaw);
void startLowBattAlarm();
void stopLowBattAlarm();
/** @brief Arm system */
void armSystem();
/** @brief Disable the motors */
void disarmSystem();
/** @brief Set the values for the manual control of the vehicle */
void setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons);
/** @brief Receive a button pressed event from an input device, e.g. joystick */
void receiveButton(int buttonIndex);
/** @brief Add a link associated with this robot */
void addLink(LinkInterface* link);
/** @brief Remove a link associated with this robot */
void removeLink(QObject* object);
/** @brief Receive a message from one of the communication links. */
virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
#ifdef QGC_PROTOBUF_ENABLED
/** @brief Receive a message from one of the communication links. */
virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
#endif
/** @brief Send a message over this link (to this or to all UAS on this link) */
void sendMessage(LinkInterface* link, mavlink_message_t message);
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void sendMessage(mavlink_message_t message);
/** @brief Temporary Hack for sending packets to patch Antenna. Send a message over all serial links except for this UAS's */
void forwardMessage(mavlink_message_t message);
/** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
void setSelected();
/** @brief Set current mode of operation, e.g. auto or manual */
void setMode(int mode);
/** @brief Request all parameters */
void requestParameters();
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
/** @brief Request a single parameter by index */
void requestParameter(int component, int id);
/** @brief Set a system parameter */
void setParameter(const int component, const QString& id, const QVariant& value);
/** @brief Write parameters to permanent storage */
void writeParametersToStorage();
/** @brief Read parameters from permanent storage */
void readParametersFromStorage();
/** @brief Get the names of all parameters */
QList<QString> getParameterNames(int component);
/** @brief Get the ids of all components */
QList<int> getComponentIds();
void enableAllDataTransmission(int rate);
void enableRawSensorDataTransmission(int rate);
void enableExtendedSystemStatusTransmission(int rate);
void enableRCChannelDataTransmission(int rate);
void enableRawControllerDataTransmission(int rate);
//void enableRawSensorFusionTransmission(int rate);
void enablePositionTransmission(int rate);
void enableExtra1Transmission(int rate);
void enableExtra2Transmission(int rate);
void enableExtra3Transmission(int rate);
/** @brief Update the system state */
void updateState();
/** @brief Set world frame origin at current GPS position */
void setLocalOriginAtCurrentGPSPosition();
/** @brief Set world frame origin / home position at this GPS position */
void setHomePosition(double lat, double lon, double alt);
/** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw);
/** @brief Add an offset in body frame to the setpoint */
void setLocalPositionOffset(float x, float y, float z, float yaw);
void startRadioControlCalibration();
void startMagnetometerCalibration();
void startGyroscopeCalibration();
void startPressureCalibration();
void startDataRecording();
void stopDataRecording();
void deleteSettings();
signals:
/** @brief The main/battery voltage has changed/was updated */
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
/** @brief An actuator value has changed */
//void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
/** @brief An actuator value has changed */
void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value);
void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value);
/** @brief The system load (MCU/CPU usage) changed */
void loadChanged(UASInterface* uas, double load);
/** @brief Propagate a heartbeat received from the system */
//void heartbeat(UASInterface* uas); // Defined in UASInterface already
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
/** @brief HIL controls have changed */
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
/** @brief HIL actuator outputs have changed */
void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0);
/** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
quint64 getUnixTimeFromMs(quint64 time);
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64 getUnixReferenceTime(quint64 time);
int componentID[256];
bool componentMulti[256];
bool connectionLost; ///< Flag indicates a timed out connection
quint64 connectionLossTime; ///< Time the connection was interrupted
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured
quint64 lastNonNullTime; ///< The last timestamp from the MAV that was not null
unsigned int onboardTimeOffsetInvalidCount; ///< Count when the offboard time offset estimation seemed wrong
bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
protected slots:
/** @brief Write settings to disk */
void writeSettings();
/** @brief Read settings from disk */
void readSettings();
// // MESSAGE RECEPTION
// /** @brief Receive a named value message */
// void receiveMessageNamedValue(const mavlink_message_t& message);
private:
// unsigned int mode; ///< The current mode of the MAV
};
#endif // _UAS_H_
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of Unmanned Aerial Vehicle object
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _UAS_H_
#define _UAS_H_
#include "UASInterface.h"
#include <MAVLinkProtocol.h>
#include <QVector3D>
#include "QGCMAVLink.h"
#include "QGCHilLink.h"
#include "QGCFlightGearLink.h"
#include "QGCXPlaneLink.h"
/**
* @brief A generic MAVLINK-connected MAV/UAV
*
* This class represents one vehicle. It can be used like the real vehicle, e.g. a call to halt()
* will automatically send the appropriate messages to the vehicle. The vehicle state will also be
* automatically updated by the comm architecture, so when writing code to e.g. control the vehicle
* no knowledge of the communication infrastructure is needed.
*/
class UAS : public UASInterface
{
Q_OBJECT
public:
UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS();
enum BatteryType
{
NICD = 0,
NIMH = 1,
LIION = 2,
LIPOLY = 3,
LIFE = 4,
AGZN = 5
}; ///< The type of battery used
static const int lipoFull = 4.2f; ///< 100% charged voltage
static const int lipoEmpty = 3.5f; ///< Discharged voltage
/* MANAGEMENT */
/** @brief The name of the robot */
QString getUASName(void) const;
/** @brief Get short state */
const QString& getShortState() const;
/** @brief Get short mode */
const QString& getShortMode() const;
/** @brief Translate from mode id to text */
static QString getShortModeTextFor(int id);
/** @brief Translate from mode id to audio text */
static QString getAudioModeTextFor(int id);
/** @brief Get the unique system id */
int getUASID() const;
/** @brief Get the airframe */
int getAirframe() const
{
return airframe;
}
/** @brief Get the components */
QMap<int, QString> getComponents();
/** @brief The time interval the robot is switched on */
quint64 getUptime() const;
/** @brief Get the status flag for the communication */
int getCommunicationStatus() const;
/** @brief Add one measurement and get low-passed voltage */
float filterVoltage(float value) const;
/** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks();
double getLocalX() const
{
return localX;
}
double getLocalY() const
{
return localY;
}
double getLocalZ() const
{
return localZ;
}
double getLatitude() const
{
return latitude;
}
double getLongitude() const
{
return longitude;
}
double getAltitude() const
{
return altitude;
}
virtual bool localPositionKnown() const
{
return isLocalPositionKnown;
}
virtual bool globalPositionKnown() const
{
return isGlobalPositionKnown;
}
double getRoll() const
{
return roll;
}
double getPitch() const
{
return pitch;
}
double getYaw() const
{
return yaw;
}
bool getSelected() const;
QVector3D getNedPosGlobalOffset() const
{
return nedPosGlobalOffset;
}
QVector3D getNedAttGlobalOffset() const
{
return nedAttGlobalOffset;
}
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay getOverlay()
{
QMutexLocker locker(&overlayMutex);
return overlay;
}
px::GLOverlay getOverlay(qreal& receivedTimestamp)
{
receivedTimestamp = receivedOverlayTimestamp;
QMutexLocker locker(&overlayMutex);
return overlay;
}
px::ObstacleList getObstacleList() {
QMutexLocker locker(&obstacleListMutex);
return obstacleList;
}
px::ObstacleList getObstacleList(qreal& receivedTimestamp) {
receivedTimestamp = receivedObstacleListTimestamp;
QMutexLocker locker(&obstacleListMutex);
return obstacleList;
}
px::Path getPath() {
QMutexLocker locker(&pathMutex);
return path;
}
px::Path getPath(qreal& receivedTimestamp) {
receivedTimestamp = receivedPathTimestamp;
QMutexLocker locker(&pathMutex);
return path;
}
px::PointCloudXYZRGB getPointCloud() {
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
receivedTimestamp = receivedPointCloudTimestamp;
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::RGBDImage getRGBDImage() {
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
receivedTimestamp = receivedRGBDImageTimestamp;
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
#endif
friend class UASWaypointManager;
protected: //COMMENTS FOR TEST UNIT
int uasId; ///< Unique system ID
unsigned char type; ///< UAS type (from type enum)
quint64 startTime; ///< The time the UAS was switched on
CommStatus commStatus; ///< Communication status
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
BatteryType batteryType; ///< The battery type
int cells; ///< Number of cells
UASWaypointManager waypointManager;
QList<double> actuatorValues;
QList<QString> actuatorNames;
QList<double> motorValues;
QList<QString> motorNames;
QMap<int, QString> components; ///< IDs and names of all detected onboard components
double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons
double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons
// Battery stats
float fullVoltage; ///< Voltage of the fully charged battery (100%)
float emptyVoltage; ///< Voltage of the empty battery (0%)
float startVoltage; ///< Voltage at system start
float tickVoltage; ///< Voltage where 0.1 V ticks are told
float lastTickVoltageValue; ///< The last voltage where a tick was announced
float tickLowpassVoltage; ///< Lowpass-filtered voltage for the tick announcement
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
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
uint32_t navMode; ///< The current navigation mode of the MAV
quint64 onboardTimeOffset;
bool controlRollManual; ///< status flag, true if roll is controlled manually
bool controlPitchManual; ///< status flag, true if pitch is controlled manually
bool controlYawManual; ///< status flag, true if yaw is controlled manually
bool controlThrustManual; ///< status flag, true if thrust is controlled manually
double manualRollAngle; ///< Roll angle set by human pilot (radians)
double manualPitchAngle; ///< Pitch angle set by human pilot (radians)
double manualYawAngle; ///< Yaw angle set by human pilot (radians)
double manualThrust; ///< Thrust set by human pilot (radians)
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
bool lowBattAlarm; ///< Switch if battery is low
bool positionLock; ///< Status if position information is available or not
double localX;
double localY;
double localZ;
double latitude;
double longitude;
double altitude;
double speedX; ///< True speed in X axis
double speedY; ///< True speed in Y axis
double speedZ; ///< True speed in Z axis
double roll;
double pitch;
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; ///< Quality of the transmitted image (percentage)
int imageType; ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
int imageWidth; ///< Width of the image stream
int imageHeight; ///< Width of the image stream
QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream
QImage image; ///< Image data of last completely transmitted image
quint64 imageStart;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay overlay;
QMutex overlayMutex;
qreal receivedOverlayTimestamp;
px::ObstacleList obstacleList;
QMutex obstacleListMutex;
qreal receivedObstacleListTimestamp;
px::Path path;
QMutex pathMutex;
qreal receivedPathTimestamp;
px::PointCloudXYZRGB pointCloud;
QMutex pointCloudMutex;
qreal receivedPointCloudTimestamp;
px::RGBDImage rgbdImage;
QMutex rgbdImageMutex;
qreal receivedRGBDImageTimestamp;
#endif
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
QGCUASParamManager* paramManager; ///< Parameter manager class
QString shortStateText; ///< Short textual state description
QString shortModeText; ///< Short textual mode description
bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV
quint64 lastAttitude; ///< Timestamp of last attitude measurement
QGCHilLink* simulation; ///< Hardware in the loop simulation link
bool isLocalPositionKnown; ///< If the local position has been received for this MAV
bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
bool systemIsArmed; ///< If the system is armed
QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
public:
/** @brief Set the current battery type */
void setBattery(BatteryType type, int cells);
/** @brief Estimate how much flight time is remaining */
int calculateTimeRemaining();
/** @brief Get the current charge level */
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();
/** @brief Check if vehicle is armed */
bool isArmed() const { return systemIsArmed; }
UASWaypointManager* getWaypointManager() {
return &waypointManager;
}
/** @brief Get reference to the param manager **/
QGCUASParamManager* getParamManager() const {
return paramManager;
}
/** @brief Get the HIL simulation */
QGCHilLink* getHILSimulation() const {
return simulation;
}
// TODO Will be removed
/** @brief Set reference to the param manager **/
void setParamManager(QGCUASParamManager* manager) {
paramManager = manager;
}
int getSystemType();
QString getSystemTypeName()
{
switch(type)
{
case MAV_TYPE_GENERIC:
return "GENERIC";
break;
case MAV_TYPE_FIXED_WING:
return "FIXED_WING";
break;
case MAV_TYPE_QUADROTOR:
return "QUADROTOR";
break;
case MAV_TYPE_COAXIAL:
return "COAXIAL";
break;
case MAV_TYPE_HELICOPTER:
return "HELICOPTER";
break;
case MAV_TYPE_ANTENNA_TRACKER:
return "ANTENNA_TRACKER";
break;
case MAV_TYPE_GCS:
return "GCS";
break;
case MAV_TYPE_AIRSHIP:
return "AIRSHIP";
break;
case MAV_TYPE_FREE_BALLOON:
return "FREE_BALLOON";
break;
case MAV_TYPE_ROCKET:
return "ROCKET";
break;
case MAV_TYPE_GROUND_ROVER:
return "GROUND_ROVER";
break;
case MAV_TYPE_SURFACE_BOAT:
return "BOAT";
break;
case MAV_TYPE_SUBMARINE:
return "SUBMARINE";
break;
case MAV_TYPE_HEXAROTOR:
return "HEXAROTOR";
break;
case MAV_TYPE_OCTOROTOR:
return "OCTOROTOR";
break;
case MAV_TYPE_TRICOPTER:
return "TRICOPTER";
break;
case MAV_TYPE_FLAPPING_WING:
return "FLAPPING_WING";
break;
default:
return "";
break;
}
}
QImage getImage();
void requestImage();
int getAutopilotType(){
return autopilot;
}
QString getAutopilotTypeName()
{
switch (autopilot)
{
case MAV_AUTOPILOT_GENERIC:
return "GENERIC";
break;
case MAV_AUTOPILOT_PIXHAWK:
return "PIXHAWK";
break;
case MAV_AUTOPILOT_SLUGS:
return "SLUGS";
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
return "ARDUPILOTMEGA";
break;
case MAV_AUTOPILOT_OPENPILOT:
return "OPENPILOT";
break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
return "GENERIC_WAYPOINTS_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
return "GENERIC_MISSION_NAVIGATION_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_MISSION_FULL:
return "GENERIC_MISSION_FULL";
break;
case MAV_AUTOPILOT_INVALID:
return "NO AP";
break;
case MAV_AUTOPILOT_PPZ:
return "PPZ";
break;
case MAV_AUTOPILOT_UDB:
return "UDB";
break;
case MAV_AUTOPILOT_FP:
return "FP";
break;
case MAV_AUTOPILOT_PX4:
return "PX4";
break;
default:
return "";
break;
}
}
public slots:
/** @brief Set the autopilot type */
void setAutopilotType(int apType)
{
autopilot = apType;
emit systemSpecsChanged(uasId);
}
/** @brief Set the type of airframe */
void setSystemType(int systemType);
/** @brief Set the specific airframe type */
void setAirframe(int airframe)
{
if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM))
{
this->airframe = airframe;
emit systemSpecsChanged(uasId);
}
}
/** @brief Set a new name **/
void setUASName(const QString& name);
/** @brief Executes a command **/
void executeCommand(MAV_CMD command);
/** @brief Executes a command with 7 params */
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
/** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */
QString getBatterySpecs();
/** @brief Launches the system **/
void launch();
/** @brief Write this waypoint to the list of waypoints */
//void setWaypoint(Waypoint* wp); FIXME tbd
/** @brief Set currently active waypoint */
//void setWaypointActive(int id); FIXME tbd
/** @brief Order the robot to return home **/
void home();
/** @brief Order the robot to land **/
void land();
void halt();
void go();
/** @brief Enable / disable HIL */
void enableHilFlightGear(bool enable, QString options);
void enableHilXPlane(bool enable);
/** @brief Send the full HIL state to the MAV */
void sendHilState( uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc);
/** @brief Places the UAV in Hardware-in-the-Loop simulation status **/
void startHil();
/** @brief Stops the UAV's Hardware-in-the-Loop simulation status **/
void stopHil();
/** @brief Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
void emergencySTOP();
/** @brief Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
bool emergencyKILL();
/** @brief Shut the system cleanly down. Will shut down any onboard computers **/
void shutdown();
/** @brief Set the target position for the robot to navigate to. */
void setTargetPosition(float x, float y, float z, float yaw);
void startLowBattAlarm();
void stopLowBattAlarm();
/** @brief Arm system */
void armSystem();
/** @brief Disable the motors */
void disarmSystem();
/** @brief Set the values for the manual control of the vehicle */
void setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons);
/** @brief Receive a button pressed event from an input device, e.g. joystick */
void receiveButton(int buttonIndex);
/** @brief Set the values for the 6dof manual control of the vehicle */
void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
/** @brief Add a link associated with this robot */
void addLink(LinkInterface* link);
/** @brief Remove a link associated with this robot */
void removeLink(QObject* object);
/** @brief Receive a message from one of the communication links. */
virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
#ifdef QGC_PROTOBUF_ENABLED
/** @brief Receive a message from one of the communication links. */
virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
#endif
/** @brief Send a message over this link (to this or to all UAS on this link) */
void sendMessage(LinkInterface* link, mavlink_message_t message);
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void sendMessage(mavlink_message_t message);
/** @brief Temporary Hack for sending packets to patch Antenna. Send a message over all serial links except for this UAS's */
void forwardMessage(mavlink_message_t message);
/** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
void setSelected();
/** @brief Set current mode of operation, e.g. auto or manual */
void setMode(int mode);
/** @brief Request all parameters */
void requestParameters();
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
/** @brief Request a single parameter by index */
void requestParameter(int component, int id);
/** @brief Set a system parameter */
void setParameter(const int component, const QString& id, const QVariant& value);
/** @brief Write parameters to permanent storage */
void writeParametersToStorage();
/** @brief Read parameters from permanent storage */
void readParametersFromStorage();
/** @brief Get the names of all parameters */
QList<QString> getParameterNames(int component);
/** @brief Get the ids of all components */
QList<int> getComponentIds();
void enableAllDataTransmission(int rate);
void enableRawSensorDataTransmission(int rate);
void enableExtendedSystemStatusTransmission(int rate);
void enableRCChannelDataTransmission(int rate);
void enableRawControllerDataTransmission(int rate);
//void enableRawSensorFusionTransmission(int rate);
void enablePositionTransmission(int rate);
void enableExtra1Transmission(int rate);
void enableExtra2Transmission(int rate);
void enableExtra3Transmission(int rate);
/** @brief Update the system state */
void updateState();
/** @brief Set world frame origin at current GPS position */
void setLocalOriginAtCurrentGPSPosition();
/** @brief Set world frame origin / home position at this GPS position */
void setHomePosition(double lat, double lon, double alt);
/** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw);
/** @brief Add an offset in body frame to the setpoint */
void setLocalPositionOffset(float x, float y, float z, float yaw);
void startRadioControlCalibration();
void startMagnetometerCalibration();
void startGyroscopeCalibration();
void startPressureCalibration();
void startDataRecording();
void stopDataRecording();
void deleteSettings();
signals:
/** @brief The main/battery voltage has changed/was updated */
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
/** @brief An actuator value has changed */
//void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
/** @brief An actuator value has changed */
void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value);
void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value);
/** @brief The system load (MCU/CPU usage) changed */
void loadChanged(UASInterface* uas, double load);
/** @brief Propagate a heartbeat received from the system */
//void heartbeat(UASInterface* uas); // Defined in UASInterface already
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
/** @brief HIL controls have changed */
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
/** @brief HIL actuator outputs have changed */
void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0);
/** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
quint64 getUnixTimeFromMs(quint64 time);
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64 getUnixReferenceTime(quint64 time);
int componentID[256];
bool componentMulti[256];
bool connectionLost; ///< Flag indicates a timed out connection
quint64 connectionLossTime; ///< Time the connection was interrupted
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured
quint64 lastNonNullTime; ///< The last timestamp from the MAV that was not null
unsigned int onboardTimeOffsetInvalidCount; ///< Count when the offboard time offset estimation seemed wrong
bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
protected slots:
/** @brief Write settings to disk */
void writeSettings();
/** @brief Read settings from disk */
void readSettings();
// // MESSAGE RECEPTION
// /** @brief Receive a named value message */
// void receiveMessageNamedValue(const mavlink_message_t& message);
private:
// unsigned int mode; ///< The current mode of the MAV
};
#endif // _UAS_H_
This source diff could not be displayed because it is too large. You can view the blob instead.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of class MainWindow
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _MAINWINDOW_H_
#define _MAINWINDOW_H_
#include <QtGui/QMainWindow>
#include <QStatusBar>
#include <QStackedWidget>
#include <QSettings>
#include <qlist.h>
#include "ui_MainWindow.h"
#include "LinkManager.h"
#include "LinkInterface.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASControlWidget.h"
#include "Linecharts.h"
#include "UASInfoWidget.h"
#include "WaypointList.h"
#include "CameraView.h"
#include "UASListWidget.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
#include "ObjectDetectionView.h"
#include "HUD.h"
#include "JoystickWidget.h"
#include "input/JoystickInput.h"
#include "DebugConsole.h"
#include "ParameterInterface.h"
#include "XMLCommProtocolWidget.h"
#include "HDDisplay.h"
#include "WatchdogControl.h"
#include "HSIDisplay.h"
#include "QGCDataPlot2D.h"
#include "QGCRemoteControlView.h"
#include "opmapcontrol.h"
#if (defined Q_OS_MAC) | (defined _MSC_VER)
#include "QGCGoogleEarthView.h"
#endif
#include "QGCToolBar.h"
#include "SlugsDataSensorView.h"
#include "LogCompressor.h"
#include "SlugsHilSim.h"
#include "SlugsPadCameraControl.h"
#include "UASControlParameters.h"
#include "QGCMAVLinkInspector.h"
#include "QGCMAVLinkLogPlayer.h"
#include "QGCVehicleConfig.h"
#include "MAVLinkDecoder.h"
class QGCMapTool;
class QGCMAVLinkMessageSender;
class QGCFirmwareUpdate;
class QSplashScreen;
/**
* @brief Main Application Window
*
**/
class MainWindow : public QMainWindow
{
Q_OBJECT
public:
static MainWindow* instance(QSplashScreen* screen = 0);
~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;
}
/** @brief Get low power mode setting */
bool lowPowerModeEnabled()
{
return lowPowerMode;
}
QList<QAction*> listLinkMenuActions(void);
public slots:
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status, int timeout);
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status);
/** @brief Shows a critical message as popup or as widget */
void showCriticalMessage(const QString& title, const QString& message);
/** @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();
/** @brief Set the currently controlled UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Add a new UAS */
void UASCreated(UASInterface* uas);
/** Delete an UAS */
void UASDeleted(UASInterface* uas);
/** @brief Update system specs of a UAS */
void UASSpecsChanged(int uas);
void startVideoCapture();
void stopVideoCapture();
void saveScreen();
/** @brief Load default view when no MAV is connected */
void loadUnconnectedView();
/** @brief Load view for pilot */
void loadPilotView();
/** @brief Load view for engineer */
void loadEngineerView();
/** @brief Load view for operator */
void loadOperatorView();
/** @brief Load MAVLink XML generator view */
void loadMAVLinkView();
/** @brief Load firmware update view */
void loadFirmwareUpdateView();
/** @brief Show the online help for users */
void showHelp();
/** @brief Show the authors / credits */
void showCredits();
/** @brief Show the project roadmap */
void showRoadMap();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
/** @brief Let the user select the CSS style sheet */
void selectStylesheet();
/** @brief Automatically reconnect last link */
void enableAutoReconnect(bool enabled);
/** @brief Save power by reducing update rates */
void enableLowPowerMode(bool enabled) { lowPowerMode = 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();
/** @brief Load a custom tool widget from a file chosen by user (QFileDialog) */
void loadCustomWidget();
/** @brief Load a custom tool widget from a file */
void loadCustomWidget(const QString& fileName, bool singleinstance=false);
/** @brief Load custom widgets from default file */
void loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType);
/** @brief Loads and shows the HIL Configuration Widget for the given UAS*/
void showHILConfigurationWidget(UASInterface *uas);
void closeEvent(QCloseEvent* event);
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/**
* @brief Shows a Docked Widget based on the action sender
*
* This slot is written to be used in conjunction with the addTool() function
* It shows the QDockedWidget based on the action sender
*
*/
void showTool(bool visible);
/**
* @brief Shows a Widget from the center stack based on the action sender
*
* This slot is written to be used in conjunction with the addCentralWidget() function
* It shows the Widget based on the action sender
*
*/
void showCentralWidget();
/** @brief Update the window name */
void configureWindowName();
signals:
void initStatusChanged(const QString& message);
public:
QGCMAVLinkLogPlayer* getLogPlayer()
{
return logPlayer;
}
MAVLinkProtocol* getMAVLink()
{
return mavlink;
}
protected:
MainWindow(QWidget *parent = 0);
typedef enum _VIEW_SECTIONS
{
VIEW_ENGINEER,
VIEW_OPERATOR,
VIEW_PILOT,
VIEW_MAVLINK,
VIEW_FIRMWAREUPDATE,
VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available
VIEW_FULL ///< All widgets shown at once
} VIEW_SECTIONS;
/**
* @brief Adds an already instantiated QDockedWidget to the Tools Menu
*
* This function does all the hosekeeping to have a QDockedWidget added to the
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item
*
* @param widget The QDockWidget being added
* @param title The entry that will appear in the Menu and in the QDockedWidget title bar
* @param location The default location for the QDockedWidget in case there is no previous key in the settings
*/
void addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea location=Qt::RightDockWidgetArea);
/**
* @brief Adds an already instantiated QWidget to the center stack
*
* This function does all the hosekeeping to have a QWidget added to the tools menu
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item. This is used for all the central widgets (those in
* the center stack.
*
* @param widget The QWidget being added
* @param title The entry that will appear in the Menu
*/
void addCentralWidget(QWidget* widget, const QString& title);
/** @brief Catch window resize events */
void resizeEvent(QResizeEvent * event);
/** @brief Keeps track of the current view */
VIEW_SECTIONS currentView;
QGC_MAINWINDOW_STYLE currentStyle;
bool aboutToCloseFlag;
bool changingViewsFlag;
void storeViewState();
void loadViewState();
void buildCustomWidget();
void buildCommonWidgets();
void connectCommonWidgets();
void connectCommonActions();
void connectSenseSoarActions();
void loadSettings();
void storeSettings();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
MAVLinkSimulationLink* simulationLink;
LinkInterface* udpLink;
QSettings settings;
QStackedWidget *centerStack;
QActionGroup* centerStackActionGroup;
// Center widgets
QPointer<Linecharts> linechartWidget;
QPointer<HUD> hudWidget;
QPointer<QGCVehicleConfig> configWidget;
QPointer<QGCMapTool> mapWidget;
QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget;
#ifdef QGC_OSG_ENABLED
QPointer<QWidget> _3DWidget;
#endif
#if (defined _MSC_VER) || (defined Q_OS_MAC)
QPointer<QGCGoogleEarthView> gEarthWidget;
#endif
QPointer<QGCFirmwareUpdate> firmwareUpdateWidget;
// Dock widgets
QPointer<QDockWidget> controlDockWidget;
QPointer<QDockWidget> controlParameterWidget;
QPointer<QDockWidget> infoDockWidget;
QPointer<QDockWidget> cameraDockWidget;
QPointer<QDockWidget> listDockWidget;
QPointer<QDockWidget> waypointsDockWidget;
QPointer<QDockWidget> detectionDockWidget;
QPointer<QDockWidget> debugConsoleDockWidget;
QPointer<QDockWidget> parametersDockWidget;
QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> video1DockWidget;
QPointer<QDockWidget> video2DockWidget;
QPointer<QDockWidget> rgbd1DockWidget;
QPointer<QDockWidget> rgbd2DockWidget;
QPointer<QDockWidget> logPlayerDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> hudDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsHilSimWidget;
QPointer<QDockWidget> slugsCamControlWidget;
QPointer<QGCToolBar> toolBar;
QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<MAVLinkDecoder> mavlinkDecoder;
QPointer<QDockWidget> mavlinkSenderWidget;
QGCMAVLinkLogPlayer* logPlayer;
// Popup widgets
JoystickWidget* joystickWidget;
JoystickInput* joystick;
/** User interface actions **/
QAction* connectUASAct;
QAction* disconnectUASAct;
QAction* startUASAct;
QAction* returnUASAct;
QAction* stopUASAct;
QAction* killUASAct;
QAction* simulateUASAct;
LogCompressor* comp;
QString screenFileName;
QTimer* videoTimer;
QString styleFileName;
bool autoReconnect;
Qt::WindowStates windowStateVal;
bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
QGCFlightGearLink* fgLink;
QTimer windowNameUpdateTimer;
private:
Ui::MainWindow ui;
QString getWindowStateKey();
QString getWindowGeometryKey();
};
#endif /* _MAINWINDOW_H_ */
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of class MainWindow
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _MAINWINDOW_H_
#define _MAINWINDOW_H_
#include <QtGui/QMainWindow>
#include <QStatusBar>
#include <QStackedWidget>
#include <QSettings>
#include <qlist.h>
#include "ui_MainWindow.h"
#include "LinkManager.h"
#include "LinkInterface.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASControlWidget.h"
#include "Linecharts.h"
#include "UASInfoWidget.h"
#include "WaypointList.h"
#include "CameraView.h"
#include "UASListWidget.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
#include "ObjectDetectionView.h"
#include "HUD.h"
#include "JoystickWidget.h"
#include "input/JoystickInput.h"
#if (defined MOUSE_ENABLED_WIN) | (defined MOUSE_ENABLED_LINUX)
#include "Mouse6dofInput.h"
#endif // MOUSE_ENABLED_WIN
#include "DebugConsole.h"
#include "ParameterInterface.h"
#include "XMLCommProtocolWidget.h"
#include "HDDisplay.h"
#include "WatchdogControl.h"
#include "HSIDisplay.h"
#include "QGCDataPlot2D.h"
#include "QGCRemoteControlView.h"
#include "opmapcontrol.h"
#if (defined Q_OS_MAC) | (defined _MSC_VER)
#include "QGCGoogleEarthView.h"
#endif
#include "QGCToolBar.h"
#include "SlugsDataSensorView.h"
#include "LogCompressor.h"
#include "SlugsHilSim.h"
#include "SlugsPadCameraControl.h"
#include "UASControlParameters.h"
#include "QGCMAVLinkInspector.h"
#include "QGCMAVLinkLogPlayer.h"
#include "QGCVehicleConfig.h"
#include "MAVLinkDecoder.h"
class QGCMapTool;
class QGCMAVLinkMessageSender;
class QGCFirmwareUpdate;
class QSplashScreen;
/**
* @brief Main Application Window
*
**/
class MainWindow : public QMainWindow
{
Q_OBJECT
public:
static MainWindow* instance(QSplashScreen* screen = 0);
~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;
}
/** @brief Get low power mode setting */
bool lowPowerModeEnabled()
{
return lowPowerMode;
}
QList<QAction*> listLinkMenuActions(void);
public slots:
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status, int timeout);
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status);
/** @brief Shows a critical message as popup or as widget */
void showCriticalMessage(const QString& title, const QString& message);
/** @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();
/** @brief Set the currently controlled UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Add a new UAS */
void UASCreated(UASInterface* uas);
/** Delete an UAS */
void UASDeleted(UASInterface* uas);
/** @brief Update system specs of a UAS */
void UASSpecsChanged(int uas);
void startVideoCapture();
void stopVideoCapture();
void saveScreen();
/** @brief Load default view when no MAV is connected */
void loadUnconnectedView();
/** @brief Load view for pilot */
void loadPilotView();
/** @brief Load view for engineer */
void loadEngineerView();
/** @brief Load view for operator */
void loadOperatorView();
/** @brief Load MAVLink XML generator view */
void loadMAVLinkView();
/** @brief Load firmware update view */
void loadFirmwareUpdateView();
/** @brief Show the online help for users */
void showHelp();
/** @brief Show the authors / credits */
void showCredits();
/** @brief Show the project roadmap */
void showRoadMap();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
/** @brief Let the user select the CSS style sheet */
void selectStylesheet();
/** @brief Automatically reconnect last link */
void enableAutoReconnect(bool enabled);
/** @brief Save power by reducing update rates */
void enableLowPowerMode(bool enabled) { lowPowerMode = 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();
/** @brief Load a custom tool widget from a file chosen by user (QFileDialog) */
void loadCustomWidget();
/** @brief Load a custom tool widget from a file */
void loadCustomWidget(const QString& fileName, bool singleinstance=false);
/** @brief Load custom widgets from default file */
void loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType);
/** @brief Loads and shows the HIL Configuration Widget for the given UAS*/
void showHILConfigurationWidget(UASInterface *uas);
void closeEvent(QCloseEvent* event);
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/**
* @brief Shows a Docked Widget based on the action sender
*
* This slot is written to be used in conjunction with the addTool() function
* It shows the QDockedWidget based on the action sender
*
*/
void showTool(bool visible);
/**
* @brief Shows a Widget from the center stack based on the action sender
*
* This slot is written to be used in conjunction with the addCentralWidget() function
* It shows the Widget based on the action sender
*
*/
void showCentralWidget();
/** @brief Update the window name */
void configureWindowName();
signals:
void initStatusChanged(const QString& message);
#ifdef MOUSE_ENABLED_LINUX
/** @brief Forward X11Event to catch 3DMouse inputs */
void x11EventOccured(XEvent *event);
#endif //MOUSE_ENABLED_LINUX
public:
QGCMAVLinkLogPlayer* getLogPlayer()
{
return logPlayer;
}
MAVLinkProtocol* getMAVLink()
{
return mavlink;
}
protected:
MainWindow(QWidget *parent = 0);
typedef enum _VIEW_SECTIONS
{
VIEW_ENGINEER,
VIEW_OPERATOR,
VIEW_PILOT,
VIEW_MAVLINK,
VIEW_FIRMWAREUPDATE,
VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available
VIEW_FULL ///< All widgets shown at once
} VIEW_SECTIONS;
/**
* @brief Adds an already instantiated QDockedWidget to the Tools Menu
*
* This function does all the hosekeeping to have a QDockedWidget added to the
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item
*
* @param widget The QDockWidget being added
* @param title The entry that will appear in the Menu and in the QDockedWidget title bar
* @param location The default location for the QDockedWidget in case there is no previous key in the settings
*/
void addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea location=Qt::RightDockWidgetArea);
/**
* @brief Adds an already instantiated QWidget to the center stack
*
* This function does all the hosekeeping to have a QWidget added to the tools menu
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item. This is used for all the central widgets (those in
* the center stack.
*
* @param widget The QWidget being added
* @param title The entry that will appear in the Menu
*/
void addCentralWidget(QWidget* widget, const QString& title);
/** @brief Catch window resize events */
void resizeEvent(QResizeEvent * event);
/** @brief Keeps track of the current view */
VIEW_SECTIONS currentView;
QGC_MAINWINDOW_STYLE currentStyle;
bool aboutToCloseFlag;
bool changingViewsFlag;
void storeViewState();
void loadViewState();
void buildCustomWidget();
void buildCommonWidgets();
void connectCommonWidgets();
void connectCommonActions();
void connectSenseSoarActions();
void loadSettings();
void storeSettings();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
MAVLinkSimulationLink* simulationLink;
LinkInterface* udpLink;
QSettings settings;
QStackedWidget *centerStack;
QActionGroup* centerStackActionGroup;
// Center widgets
QPointer<Linecharts> linechartWidget;
QPointer<HUD> hudWidget;
QPointer<QGCVehicleConfig> configWidget;
QPointer<QGCMapTool> mapWidget;
QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget;
#ifdef QGC_OSG_ENABLED
QPointer<QWidget> _3DWidget;
#endif
#if (defined _MSC_VER) || (defined Q_OS_MAC)
QPointer<QGCGoogleEarthView> gEarthWidget;
#endif
QPointer<QGCFirmwareUpdate> firmwareUpdateWidget;
// Dock widgets
QPointer<QDockWidget> controlDockWidget;
QPointer<QDockWidget> controlParameterWidget;
QPointer<QDockWidget> infoDockWidget;
QPointer<QDockWidget> cameraDockWidget;
QPointer<QDockWidget> listDockWidget;
QPointer<QDockWidget> waypointsDockWidget;
QPointer<QDockWidget> detectionDockWidget;
QPointer<QDockWidget> debugConsoleDockWidget;
QPointer<QDockWidget> parametersDockWidget;
QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> video1DockWidget;
QPointer<QDockWidget> video2DockWidget;
QPointer<QDockWidget> rgbd1DockWidget;
QPointer<QDockWidget> rgbd2DockWidget;
QPointer<QDockWidget> logPlayerDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> hudDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsHilSimWidget;
QPointer<QDockWidget> slugsCamControlWidget;
QPointer<QGCToolBar> toolBar;
QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<MAVLinkDecoder> mavlinkDecoder;
QPointer<QDockWidget> mavlinkSenderWidget;
QGCMAVLinkLogPlayer* logPlayer;
// Popup widgets
JoystickWidget* joystickWidget;
JoystickInput* joystick;
#ifdef MOUSE_ENABLED_WIN
/** @brief 3d Mouse support (WIN only) */
Mouse3DInput* mouseInput; ///< 3dConnexion 3dMouse SDK
Mouse6dofInput* mouse; ///< Implementation for 3dMouse input
#endif // MOUSE_ENABLED_WIN
#ifdef MOUSE_ENABLED_LINUX
/** @brief Reimplementation of X11Event to handle 3dMouse Events (magellan) */
bool x11Event(XEvent *event);
Mouse6dofInput* mouse; ///< Implementation for 3dMouse input
#endif // MOUSE_ENABLED_LINUX
/** User interface actions **/
QAction* connectUASAct;
QAction* disconnectUASAct;
QAction* startUASAct;
QAction* returnUASAct;
QAction* stopUASAct;
QAction* killUASAct;
QAction* simulateUASAct;
LogCompressor* comp;
QString screenFileName;
QTimer* videoTimer;
QString styleFileName;
bool autoReconnect;
Qt::WindowStates windowStateVal;
bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
QGCFlightGearLink* fgLink;
QTimer windowNameUpdateTimer;
private:
Ui::MainWindow ui;
QString getWindowStateKey();
QString getWindowGeometryKey();
};
#endif /* _MAINWINDOW_H_ */
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