diff --git a/.gitignore b/.gitignore index 83a4731f819fc5c6a5f92e0af015710475347742..cf34ac8aadac498e894176d70c9a9c87d494f982 100644 --- a/.gitignore +++ b/.gitignore @@ -47,6 +47,8 @@ user_config.pri *.cproject *.sln *.suo +*.uhf.txt +*.opensdf thirdParty/qserialport-build-desktop/ thirdParty/qserialport/bin/ diff --git a/files/px4/widgets/px4_mc_position_pid_params.qgw b/files/px4/widgets/px4_mc_position_pid_params.qgw new file mode 100644 index 0000000000000000000000000000000000000000..1931dfa3b912adac6f5185a7bfee217e3dee332a --- /dev/null +++ b/files/px4/widgets/px4_mc_position_pid_params.qgw @@ -0,0 +1,72 @@ +[PX4%20Multirotor%20Attitude%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Attitude P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=MC_ATT_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1.5 +QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Attitude I Gain +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=MC_ATT_I +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Attitude D Gain +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=MC_ATT_D +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Anti-Windup +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=MC_ATT_AWU +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\5\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Output Limit +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_PARAMID=MC_ATT_LIM +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MAX=3 +QGC_TOOL_WIDGET_ITEMS\6\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw P Gain +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_P +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MAX=1.2 +QGC_TOOL_WIDGET_ITEMS\7\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw D Gain +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_D +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\8\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate P Gain +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_P +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MAX=1.5 +QGC_TOOL_WIDGET_ITEMS\9\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate D Gain +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_D +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MAX=0.3 +QGC_TOOL_WIDGET_ITEMS\10\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_DESCRIPTION=Yaw Rate P Gain +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_PARAMID=MC_YAWRATE_P +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DISPLAY_INFO=false +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\size=10 diff --git a/files/xplane/QRO_X/QRO_X.acf b/files/xplane/QRO_X/QRO_X.acf new file mode 100755 index 0000000000000000000000000000000000000000..68aa90c3859bbd7a4347804a7b52bd02c4e4c5f8 Binary files /dev/null and b/files/xplane/QRO_X/QRO_X.acf differ diff --git a/files/xplane/QRO_X/QRO_X_paint.png b/files/xplane/QRO_X/QRO_X_paint.png new file mode 100755 index 0000000000000000000000000000000000000000..502efd6824fa7a5bac8f8ca61a688090d6e5a466 Binary files /dev/null and b/files/xplane/QRO_X/QRO_X_paint.png differ diff --git a/libs/thirdParty/3DMouse/win/I3dMouseParams.h b/libs/thirdParty/3DMouse/win/I3dMouseParams.h new file mode 100644 index 0000000000000000000000000000000000000000..e8932cce03918d6983ceb29ac62bb60b7e527622 --- /dev/null +++ b/libs/thirdParty/3DMouse/win/I3dMouseParams.h @@ -0,0 +1,84 @@ +#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 diff --git a/libs/thirdParty/3DMouse/win/Mouse3DInput.cpp b/libs/thirdParty/3DMouse/win/Mouse3DInput.cpp new file mode 100644 index 0000000000000000000000000000000000000000..7b322223a37173b83cd809b45d259699b8eed66c --- /dev/null +++ b/libs/thirdParty/3DMouse/win/Mouse3DInput.cpp @@ -0,0 +1,677 @@ + +#include "Mouse3DInput.h" + +#include + +#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(SpacePilotKeys), + eSpaceExplorer + , sizeof(SpaceExplorerKeys)/sizeof(SpaceExplorerKeys[0]) + , const_cast(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; imessage == WM_INPUT) { + HRAWINPUT hRawInput = reinterpret_cast(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& 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(nDevices); + if (::GetRawInputDeviceList(&rawInputDeviceList[0], &nDevices, sizeof(RAWINPUTDEVICELIST)) == static_cast(-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(msg.lParam); + size_t cbSize = *pcbSize - cbDataSize; + if (::GetRawInputData(hRawInput, RID_INPUT, pri, &cbSize, cbSizeHeader) == static_cast(-1)) { + if (nCount==0) { + return static_cast(-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(pri) - reinterpret_cast(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::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::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 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(pBuffer); + UINT cbSize = cbSizeOfBuffer; + + if (::GetRawInputData(hRawInput, RID_INPUT, pRawInput, &cbSize, sizeof(RAWINPUTHEADER)) == static_cast(-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(-1)) { + PRAWINPUT pri = pRawInput; + UINT nInput; + for (nInput=0; nInputGetRawInputBuffer(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 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(&pRawInput->data.hid.bRawData[1]); + // Cache the pan zoom data + deviceData.fAxes[0] = static_cast(pnRawData[0]); + deviceData.fAxes[1] = static_cast(pnRawData[1]); + deviceData.fAxes[2] = static_cast(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(pnRawData[3]); + deviceData.fAxes[4] = static_cast(pnRawData[4]); + deviceData.fAxes[5] = static_cast(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(&pRawInput->data.hid.bRawData[1]); + // Cache the rotation data + deviceData.fAxes[3] = static_cast(pnRawData[0]); + deviceData.fAxes[4] = static_cast(pnRawData[1]); + deviceData.fAxes[5] = static_cast(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(&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; +} diff --git a/libs/thirdParty/3DMouse/win/Mouse3DInput.h b/libs/thirdParty/3DMouse/win/Mouse3DInput.h new file mode 100644 index 0000000000000000000000000000000000000000..71028035e2f1dbf9fd34215b1dc3cd78a3150b55 --- /dev/null +++ b/libs/thirdParty/3DMouse/win/Mouse3DInput.h @@ -0,0 +1,98 @@ +#ifndef T3DMOUSE_INPUT_H +#define T3DMOUSE_INPUT_H + +#include "MouseParameters.h" + +#include +#include +#include + +#ifndef _WIN32_WINNT +#define _WIN32_WINNT 0x0501 //target at least windows XP +#endif + +#include + + +/* + 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& motionData); +virtual void On3dmouseKeyDown(HANDLE device, int virtualKeyCode); +virtual void On3dmouseKeyUp(HANDLE device, int virtualKeyCode); + +signals: + + void Move3d(std::vector& 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 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 diff --git a/libs/thirdParty/3DMouse/win/MouseParameters.cpp b/libs/thirdParty/3DMouse/win/MouseParameters.cpp new file mode 100644 index 0000000000000000000000000000000000000000..056253fb5b59ee3683583ce3fd5d9d3b5732c76a --- /dev/null +++ b/libs/thirdParty/3DMouse/win/MouseParameters.cpp @@ -0,0 +1,88 @@ +#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; +} + diff --git a/libs/thirdParty/3DMouse/win/MouseParameters.h b/libs/thirdParty/3DMouse/win/MouseParameters.h new file mode 100644 index 0000000000000000000000000000000000000000..70f5b1b6d00f72d4241b375985c72360c50a81dd --- /dev/null +++ b/libs/thirdParty/3DMouse/win/MouseParameters.h @@ -0,0 +1,49 @@ + +#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 diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index a49a7a51c8abdcc3c01561e234506632f885dbbb..db7d448b2820d0904e0c985b27a876247eb05be9 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -1,627 +1,659 @@ -# ------------------------------------------------- -# QGroundControl - Micro Air Vehicle Groundstation -# Please see our website at -# Maintainer: -# Lorenz Meier -# (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 . -# ------------------------------------------------- - - -# 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/comm/QGCHilLink.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 +# Maintainer: +# Lorenz Meier +# (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 . +# ------------------------------------------------- + + +# 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 +} diff --git a/src/PX4FirmwareUpgradeWorker.cc b/src/PX4FirmwareUpgradeWorker.cc index 461b82d7eff7831e5417c6292ef5ae3a016b1597..b4a6755dec682c9229ffcb29872040c97654cd8d 100644 --- a/src/PX4FirmwareUpgradeWorker.cc +++ b/src/PX4FirmwareUpgradeWorker.cc @@ -1,3 +1,6 @@ +#include +#include + #include "PX4FirmwareUpgradeWorker.h" #include @@ -49,21 +52,28 @@ PX4FirmwareUpgradeWorker* PX4FirmwareUpgradeWorker::putWorkerInThread(QObject *p // Starts an event loop, and emits workerThread->started() workerThread->start(); + return worker; } -bool PX4FirmwareUpgradeWorker::startContinousScan() +void PX4FirmwareUpgradeWorker::startContinousScan() { - while (true) { - if (detect()) { - break; - } + exitThread = false; + while (!exitThread) { +// if (detect()) { +// break; +// } + QGC::SLEEP::msleep(20); } - return true; + if (exitThread) { + link->disconnect(); + delete link; + exit(0); + } } -bool PX4FirmwareUpgradeWorker::detect() +void PX4FirmwareUpgradeWorker::detect() { if (!link) { @@ -80,7 +90,7 @@ bool PX4FirmwareUpgradeWorker::detect() // Ignore known wrong link names if (ports->at(i).contains("Bluetooth")) { - continue; + //continue; } link->setPortName(ports->at(i)); @@ -101,12 +111,6 @@ bool PX4FirmwareUpgradeWorker::detect() break; } - if (insync) { - return true; - } else { - return false; - } - //ui.portName->setCurrentIndex(ui.baudRate->findText(QString("%1").arg(this->link->getPortName()))); // Set port @@ -119,11 +123,15 @@ void PX4FirmwareUpgradeWorker::receiveBytes(LinkInterface* link, QByteArray b) { for (int position = 0; position < b.size(); position++) { qDebug() << "BYTES"; - qDebug() << std::hex << (char)(b[position]); + qDebug() << (char)(b[position]); if (((const char)b[position]) == INSYNC) { qDebug() << "SYNC"; insync = true; + } + + if (insync && ((const char)b[position]) == OK) + { emit detectionStatusChanged("Found PX4 board"); } } @@ -131,7 +139,31 @@ void PX4FirmwareUpgradeWorker::receiveBytes(LinkInterface* link, QByteArray b) printf("\n"); } -bool PX4FirmwareUpgradeWorker::upgrade(const QString &filename) +void PX4FirmwareUpgradeWorker::loadFirmware(const QString &filename) +{ + qDebug() << __FILE__ << __LINE__ << "LOADING FW"; + QFile f(filename); + if (f.open(QIODevice::ReadOnly)) + { + QByteArray buf = f.readAll(); + f.close(); + firmware = QJsonDocument::fromBinaryData(buf); + if (firmware.isNull()) { + emit upgradeStatusChanged(tr("Failed decoding file %1").arg(filename)); + } else { + emit upgradeStatusChanged(tr("Ready to flash %1").arg(filename)); + } + } else { + emit upgradeStatusChanged(tr("Failed opening file %1").arg(filename)); + } +} + +void PX4FirmwareUpgradeWorker::upgrade() { + emit upgradeStatusChanged(tr("Starting firmware upgrade..")); +} +void PX4FirmwareUpgradeWorker::abort() +{ + exitThread = true; } diff --git a/src/PX4FirmwareUpgradeWorker.h b/src/PX4FirmwareUpgradeWorker.h index 88c1acda3dca866fa968af6c0f7ed11d9abff6af..873eadc357f2ccf139b8916e8204e9b1a0bb973f 100644 --- a/src/PX4FirmwareUpgradeWorker.h +++ b/src/PX4FirmwareUpgradeWorker.h @@ -2,6 +2,7 @@ #define PX4FIRMWAREUPGRADEWORKER_H #include +#include #include @@ -24,7 +25,7 @@ public slots: * @brief Continously scan for bootloaders * @return */ - bool startContinousScan(); + void startContinousScan(); /** * @brief Detect connected PX4 bootloaders @@ -34,14 +35,19 @@ public slots: * * @return true if found on one link, false else */ - bool detect(); + void detect(); /** * @brief Upgrade the firmware using the currently connected link * @param filename file name / path of the firmware file - * @return true if upgrade succeeds, false else */ - bool upgrade(const QString &filename); + void upgrade(); + + /** + * @brief Load firmware from disk into memory + * @param filename + */ + void loadFirmware(const QString &filename); /** * @brief Receive bytes from a link @@ -50,9 +56,18 @@ public slots: */ void receiveBytes(LinkInterface* link, QByteArray b); + /** + * @brief Abort upgrade worker + */ + void abort(); + +protected: + bool exitThread; + private: SerialLink *link; bool insync; + QJsonDocument firmware; }; #endif // PX4FIRMWAREUPGRADEWORKER_H diff --git a/src/apps/qupgrade/QUpgradeApp.cc b/src/apps/qupgrade/QUpgradeApp.cc index 1ca955b3ac9c4202e8e80a2caf06f847eada1412..558845aeb8819bb234d054db7306c8f5f393aa38 100644 --- a/src/apps/qupgrade/QUpgradeApp.cc +++ b/src/apps/qupgrade/QUpgradeApp.cc @@ -72,13 +72,21 @@ QUpgradeApp::QUpgradeApp(int &argc, char* argv[]) : QApplication(argc, argv) // Create main window QUpgradeMainWindow* window = new QUpgradeMainWindow(); + PX4FirmwareUpgrader *upgrader = new PX4FirmwareUpgrader(window); + window->setCentralWidget(upgrader); // Get PX4 upgrade widget and instantiate worker thread PX4FirmwareUpgradeWorker* worker = PX4FirmwareUpgradeWorker::putWorkerInThread(this); - connect(worker, SIGNAL(detectionStatusChanged(QString)), window->firmwareUpgrader(), SLOT(setDetectionStatusText(QString))); - connect(worker, SIGNAL(upgradeStatusChanged(QString)), window->firmwareUpgrader(), SLOT(setFlashStatusText(QString))); - connect(worker, SIGNAL(upgradeProgressChanged(int)), window->firmwareUpgrader(), SLOT(setFlashProgress(int))); - connect(worker, SIGNAL(validPortFound(QString)), window->firmwareUpgrader(), SLOT(setPortName(QString))); + + connect(worker, SIGNAL(detectionStatusChanged(QString)), upgrader, SLOT(setDetectionStatusText(QString)), Qt::QueuedConnection); + connect(worker, SIGNAL(upgradeStatusChanged(QString)), upgrader, SLOT(setFlashStatusText(QString)), Qt::QueuedConnection); + connect(worker, SIGNAL(upgradeProgressChanged(int)), upgrader, SLOT(setFlashProgress(int)), Qt::QueuedConnection); + connect(worker, SIGNAL(validPortFound(QString)), upgrader, SLOT(setPortName(QString))); + connect(upgrader, SIGNAL(firmwareFileNameSet(QString)), worker, SLOT(loadFirmware(QString)), Qt::QueuedConnection); + connect(upgrader, SIGNAL(upgrade()), worker, SLOT(upgrade()), Qt::QueuedConnection); + connect(this, SIGNAL(lastWindowClosed()), worker, SLOT(abort()), Qt::QueuedConnection); + + worker->loadFirmware("abc"); window->setWindowTitle(applicationName() + " " + applicationVersion()); window->show(); diff --git a/src/apps/qupgrade/QUpgradeMainWindow.cc b/src/apps/qupgrade/QUpgradeMainWindow.cc index ad0bb2d186b5b027672e0c715ca637b96c015ed1..fea3841df3082351e327665584aff0caa9e3fbad 100644 --- a/src/apps/qupgrade/QUpgradeMainWindow.cc +++ b/src/apps/qupgrade/QUpgradeMainWindow.cc @@ -42,10 +42,6 @@ QUpgradeMainWindow::QUpgradeMainWindow(QWidget *parent) : ui->setupUi(this); } -PX4FirmwareUpgrader* QUpgradeMainWindow::firmwareUpgrader() { - return ui->centralwidget; -} - QUpgradeMainWindow::~QUpgradeMainWindow() { delete ui; diff --git a/src/apps/qupgrade/QUpgradeMainWindow.h b/src/apps/qupgrade/QUpgradeMainWindow.h index dbb523779376effbf358151189a31bfe49164e01..c012600dc6b3bb1e6cf8f63bdfe24f3e55b1ffa0 100644 --- a/src/apps/qupgrade/QUpgradeMainWindow.h +++ b/src/apps/qupgrade/QUpgradeMainWindow.h @@ -48,8 +48,6 @@ public: explicit QUpgradeMainWindow(QWidget *parent = 0); ~QUpgradeMainWindow(); - PX4FirmwareUpgrader* firmwareUpgrader(); - public slots: protected: diff --git a/src/apps/qupgrade/QUpgradeMainWindow.ui b/src/apps/qupgrade/QUpgradeMainWindow.ui index 75f16d006b14cb3624646d56886aee5f9e741a00..5c806bbfffa382604cc10da748d05a0ab6712e19 100644 --- a/src/apps/qupgrade/QUpgradeMainWindow.ui +++ b/src/apps/qupgrade/QUpgradeMainWindow.ui @@ -13,7 +13,7 @@ MainWindow - + @@ -28,14 +28,6 @@ - - - PX4FirmwareUpgrader - QWidget -
PX4FirmwareUpgrader.h
- 1 -
-
diff --git a/src/comm/QGCHilLink.cc b/src/comm/QGCHilLink.cc deleted file mode 100644 index 9246fa41f0ef5f29da11ed0ee398d4629a152a04..0000000000000000000000000000000000000000 --- a/src/comm/QGCHilLink.cc +++ /dev/null @@ -1,6 +0,0 @@ -#include "QGCHilLink.h" - -//QGCHilLink::QGCHilLink(QObject *parent) : -// QThread(parent) -//{ -//} diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index 723a980738446352b0b8859905986ccac3f648f3..521beb5b6092b00da986324a3fa1f652f37a96fb 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -49,7 +49,10 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress terraSync(NULL), airframeID(QGCXPlaneLink::AIRFRAME_UNKNOWN), xPlaneConnected(false), - xPlaneVersion(0) + xPlaneVersion(0), + simUpdateLast(QGC::groundTimeMilliseconds()), + simUpdateLastText(QGC::groundTimeMilliseconds()), + simUpdateHz(0) { this->localHost = localHost; this->localPort = localPort/*+mav->getUASID()*/; @@ -223,10 +226,12 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost) void QGCXPlaneLink::updateActuators(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8) { + // XXX Control this via the onboard system type exclusively + if (mav->getSystemType() == MAV_TYPE_QUADROTOR) // Only update this for multirotors - if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C || - airframeID == AIRFRAME_QUAD_X_ARDRONE || - airframeID == AIRFRAME_QUAD_DJI_F450_PWM) +// if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C || +// airframeID == AIRFRAME_QUAD_X_ARDRONE || +// airframeID == AIRFRAME_QUAD_DJI_F450_PWM) { Q_UNUSED(time); @@ -252,27 +257,34 @@ void QGCXPlaneLink::updateActuators(uint64_t time, float act1, float act2, float p.index = 25; memset(p.f, 0, sizeof(p.f)); - if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C) - { - p.f[0] = act1 / 255.0f; - p.f[1] = act2 / 255.0f; - p.f[2] = act3 / 255.0f; - p.f[3] = act4 / 255.0f; - } - else if (airframeID == AIRFRAME_QUAD_X_ARDRONE) - { - p.f[0] = act1 / 500.0f; - p.f[1] = act2 / 500.0f; - p.f[2] = act3 / 500.0f; - p.f[3] = act4 / 500.0f; - } - else - { - p.f[0] = (act1 - 1000.0f) / 1000.0f; - p.f[1] = (act2 - 1000.0f) / 1000.0f; - p.f[2] = (act3 - 1000.0f) / 1000.0f; - p.f[3] = (act4 - 1000.0f) / 1000.0f; - } + p.f[0] = act1; + p.f[1] = act2; + p.f[2] = act3; + p.f[3] = act4; + + // XXX the system corrects for the scale onboard, do not scale again + +// if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C) +// { +// p.f[0] = act1 / 255.0f; +// p.f[1] = act2 / 255.0f; +// p.f[2] = act3 / 255.0f; +// p.f[3] = act4 / 255.0f; +// } +// else if (airframeID == AIRFRAME_QUAD_X_ARDRONE) +// { +// p.f[0] = act1 / 500.0f; +// p.f[1] = act2 / 500.0f; +// p.f[2] = act3 / 500.0f; +// p.f[3] = act4 / 500.0f; +// } +// else +// { +// p.f[0] = (act1 - 1000.0f) / 1000.0f; +// p.f[1] = (act2 - 1000.0f) / 1000.0f; +// p.f[2] = (act3 - 1000.0f) / 1000.0f; +// p.f[3] = (act4 - 1000.0f) / 1000.0f; +// } // Throttle writeBytes((const char*)&p, sizeof(p)); } @@ -282,7 +294,6 @@ void QGCXPlaneLink::updateControls(uint64_t time, float rollAilerons, float pitc { // Do not update this control type for // all multirotors - if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C || airframeID == AIRFRAME_QUAD_X_ARDRONE || airframeID == AIRFRAME_QUAD_DJI_F450_PWM) @@ -366,7 +377,7 @@ void QGCXPlaneLink::readBytes() // Only emit updates on attitude message bool emitUpdate = false; - const qint64 maxLength = 65536; + const qint64 maxLength = 1000; char data[maxLength]; QHostAddress sender; quint16 senderPort; @@ -501,8 +512,18 @@ void QGCXPlaneLink::readBytes() } // Send updated state - if (emitUpdate) + if (emitUpdate && (QGC::groundTimeMilliseconds() - simUpdateLast) > 3) { + simUpdateHz = simUpdateHz * 0.9f + 0.1f * (1000.0f / (QGC::groundTimeMilliseconds() - simUpdateLast)); + if (QGC::groundTimeMilliseconds() - simUpdateLastText > 2000) { + emit statusMessage(tr("Receiving from XPlane at %1 Hz").arg(static_cast(simUpdateHz))); + // Reset lowpass with current value + simUpdateHz = (1000.0f / (QGC::groundTimeMilliseconds() - simUpdateLast)); + // Set state + simUpdateLastText = QGC::groundTimeMilliseconds(); + } + simUpdateLast = QGC::groundTimeMilliseconds(); + emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat*1E7, lon*1E7, alt*1E3, vx, vy, vz, xacc*1000, yacc*1000, zacc*1000); @@ -510,7 +531,7 @@ void QGCXPlaneLink::readBytes() if (!oldConnectionState && xPlaneConnected) { - emit statusMessage("Receiving from XPlane."); + emit statusMessage(tr("Receiving from XPlane.")); } // // Echo data for debugging purposes diff --git a/src/comm/QGCXPlaneLink.h b/src/comm/QGCXPlaneLink.h index e389b7b8f2669f9f45ae0d0d6a7068e32bffe6aa..d89e98763a1ec68fec527c1c763e8197540e1780 100644 --- a/src/comm/QGCXPlaneLink.h +++ b/src/comm/QGCXPlaneLink.h @@ -190,6 +190,9 @@ protected: enum AIRFRAME airframeID; bool xPlaneConnected; unsigned int xPlaneVersion; + quint64 simUpdateLast; + quint64 simUpdateLastText; + float simUpdateHz; void setName(QString name); diff --git a/src/input/Mouse6dofInput.cpp b/src/input/Mouse6dofInput.cpp new file mode 100644 index 0000000000000000000000000000000000000000..cadf98b7332505fbdaee80f10de9f1b33f996385 --- /dev/null +++ b/src/input/Mouse6dofInput.cpp @@ -0,0 +1,330 @@ +/** + * @file + * @brief 3dConnexion 3dMouse interface for QGroundControl + * + * @author Matthias Krebs + * + */ + +#include "Mouse6dofInput.h" +#include "UAS.h" +#include "UASManager.h" +#include "QMessageBox" + +#ifdef MOUSE_ENABLED_LINUX +#include +#include +#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&)), this, SLOT(motion3DMouse(std::vector&))); + 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(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(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 &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 diff --git a/src/input/Mouse6dofInput.h b/src/input/Mouse6dofInput.h new file mode 100644 index 0000000000000000000000000000000000000000..61cfe8559f3bb642d024f6cc419a8969175cda1c --- /dev/null +++ b/src/input/Mouse6dofInput.h @@ -0,0 +1,94 @@ +/** + * @file + * @brief Definition of 3dConnexion 3dMouse interface for QGroundControl + * + * @author Matthias Krebs + * + */ + +#ifndef MOUSE6DOFINPUT_H +#define MOUSE6DOFINPUT_H + +#include + +#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 &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 diff --git a/src/uas/ArduPilotMegaMAV.cc b/src/uas/ArduPilotMegaMAV.cc index 99df9774fd0a2975831371f36d28d40d65b01925..767c084ce1c32626f0acf35c92c53ff41d7dd989 100644 --- a/src/uas/ArduPilotMegaMAV.cc +++ b/src/uas/ArduPilotMegaMAV.cc @@ -32,6 +32,8 @@ ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) : UAS(mavlink, id)//, // place other initializers here { + // Ask for all streams at 4 Hz + enableAllDataTransmission(4); } /** diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 124c4f0260d3a9996d8df125df8b02d9e7bf0620..1de82be74e24c150a232e5b70241de05c0ee9ee4 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1,3066 +1,3084 @@ -/*=================================================================== -======================================================================*/ - -/** - * @file - * @brief Represents one unmanned aerial vehicle - * - * @author Lorenz Meier - * - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include "UAS.h" -#include "LinkInterface.h" -#include "UASManager.h" -#include "QGC.h" -#include "GAudioOutput.h" -#include "MAVLinkProtocol.h" -#include "QGCMAVLink.h" -#include "LinkManager.h" -#include "SerialLink.h" - -#ifdef QGC_PROTOBUF_ENABLED -#include -#endif - -/** -* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs) -* by calling readSettings. This means the new UAS will have the same settings -* as the previous one created unless one calls deleteSettings in the code after -* creating the UAS. -*/ -UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), - uasId(id), - startTime(QGC::groundTimeMilliseconds()), - commStatus(COMM_DISCONNECTED), - name(""), - autopilot(-1), - links(new QList()), - unknownPackets(), - mavlink(protocol), - waypointManager(this), - thrustSum(0), - thrustMax(10), - startVoltage(-1.0f), - tickVoltage(10.5f), - lastTickVoltageValue(13.0f), - tickLowpassVoltage(12.0f), - warnVoltage(9.5f), - warnLevelPercent(20.0f), - currentVoltage(12.6f), - lpVoltage(12.0f), - batteryRemainingEstimateEnabled(true), - mode(-1), - status(-1), - navMode(-1), - onboardTimeOffset(0), - controlRollManual(true), - controlPitchManual(true), - controlYawManual(true), - controlThrustManual(true), - manualRollAngle(0), - manualPitchAngle(0), - manualYawAngle(0), - manualThrust(0), - receiveDropRate(0), - sendDropRate(0), - lowBattAlarm(false), - positionLock(false), - localX(0.0), - localY(0.0), - localZ(0.0), - latitude(0.0), - longitude(0.0), - altitude(0.0), - roll(0.0), - pitch(0.0), - yaw(0.0), - statusTimeout(new QTimer(this)), - #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - receivedOverlayTimestamp(0.0), - receivedObstacleListTimestamp(0.0), - receivedPathTimestamp(0.0), - receivedPointCloudTimestamp(0.0), - receivedRGBDImageTimestamp(0.0), - #endif - paramsOnceRequested(false), - airframe(QGC_AIRFRAME_GENERIC), - attitudeKnown(false), - paramManager(NULL), - attitudeStamped(false), - lastAttitude(0), - simulation(0), - isLocalPositionKnown(false), - isGlobalPositionKnown(false), - systemIsArmed(false), - nedPosGlobalOffset(0,0,0), - nedAttGlobalOffset(0,0,0), - connectionLost(false), - lastVoltageWarning(0), - lastNonNullTime(0), - onboardTimeOffsetInvalidCount(0), - hilEnabled(false) - -{ - for (unsigned int i = 0; i<255;++i) - { - componentID[i] = -1; - componentMulti[i] = false; - } - - color = UASInterface::getNextColor(); - setBatterySpecs(QString("9V,9.5V,12.6V")); - connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); - connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings())); - statusTimeout->start(500); - readSettings(); - type = MAV_TYPE_GENERIC; - // Initial signals - emit disarmed(); - emit armingChanged(false); -} - -/** -* Saves the settings of name, airframe, autopilot type and battery specifications -* by calling writeSettings. -*/ -UAS::~UAS() -{ - writeSettings(); - delete links; - delete statusTimeout; - delete simulation; -} - -/** -* Saves the settings of name, airframe, autopilot type and battery specifications -* for the next instantiation of UAS. -*/ -void UAS::writeSettings() -{ - QSettings settings; - settings.beginGroup(QString("MAV%1").arg(uasId)); - settings.setValue("NAME", this->name); - settings.setValue("AIRFRAME", this->airframe); - settings.setValue("AP_TYPE", this->autopilot); - settings.setValue("BATTERY_SPECS", getBatterySpecs()); - settings.endGroup(); - settings.sync(); -} - -/** -* Reads in the settings: name, airframe, autopilot type, and battery specifications -* for the new UAS. -*/ -void UAS::readSettings() -{ - QSettings settings; - settings.beginGroup(QString("MAV%1").arg(uasId)); - this->name = settings.value("NAME", this->name).toString(); - this->airframe = settings.value("AIRFRAME", this->airframe).toInt(); - this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt(); - if (settings.contains("BATTERY_SPECS")) - { - setBatterySpecs(settings.value("BATTERY_SPECS").toString()); - } - settings.endGroup(); -} - -/** -* Deletes the settings origianally read into the UAS by readSettings. -* This is in case one does not want the old values but would rather -* start with the values assigned by the constructor. -*/ -void UAS::deleteSettings() -{ - this->name = ""; - this->airframe = QGC_AIRFRAME_GENERIC; - this->autopilot = -1; - setBatterySpecs(QString("9V,9.5V,12.6V")); -} - -/** -* @ return the id of the uas -*/ -int UAS::getUASID() const -{ - return uasId; -} - -/** -* Update the heartbeat. -*/ -void UAS::updateState() -{ - // Check if heartbeat timed out - quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat; - if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat)) - { - connectionLost = true; - QString audiostring = QString("Link lost to system %1").arg(this->getUASID()); - GAudioOutput::instance()->say(audiostring.toLower()); - } - - // Update connection loss time on each iteration - if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat)) - { - connectionLossTime = heartbeatInterval; - emit heartbeatTimeout(true, heartbeatInterval/1000); - } - - // Connection gained - if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat)) - { - QString audiostring = QString("Link regained to system %1 after %2 seconds").arg(this->getUASID()).arg((int)(connectionLossTime/1000000)); - GAudioOutput::instance()->say(audiostring.toLower()); - connectionLost = false; - connectionLossTime = 0; - emit heartbeatTimeout(false, 0); - } - - // Position lock is set by the MAVLink message handler - // if no position lock is available, indicate an error - if (positionLock) - { - positionLock = false; - } - else - { - if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock) - { - GAudioOutput::instance()->notifyNegative(); - } - } - -//#define MAVLINK_OFFBOARD_CONTROL_MODE_NONE 0 -//#define MAVLINK_OFFBOARD_CONTROL_MODE_RATES 1 -//#define MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE 2 -//#define MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY 3 -//#define MAVLINK_OFFBOARD_CONTROL_MODE_POSITION 4 -//#define MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED 0x10 - -//#warning THIS IS A HUGE HACK AND SHOULD NEVER SHOW UP IN ANY GIT REPOSITORY -// mavlink_message_t message; - -// mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t sp; - -// sp.group = 0; - -// /* set rate mode, set zero rates and 20% throttle */ -// sp.mode = MAVLINK_OFFBOARD_CONTROL_MODE_RATES | MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED; - -// sp.roll[0] = INT16_MAX * 0.0f; -// sp.pitch[0] = INT16_MAX * 0.0f; -// sp.yaw[0] = INT16_MAX * 0.0f; -// sp.thrust[0] = UINT16_MAX * 0.3f; - - -// /* send from system 200 and component 0 */ -// mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(200, 0, &message, &sp); - -// sendMessage(message); -} - -/** -* If the acitve UAS (the UAS that was selected) is not the one that is currently -* active, then change the active UAS to the one that was selected. -*/ -void UAS::setSelected() -{ - if (UASManager::instance()->getActiveUAS() != this) - { - UASManager::instance()->setActiveUAS(this); - emit systemSelected(true); - } -} - -/** -* @return if the active UAS is the current UAS -**/ -bool UAS::getSelected() const -{ - return (UASManager::instance()->getActiveUAS() == this); -} - -void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) -{ - if (!link) return; - if (!links->contains(link)) - { - addLink(link); - // qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName(); - } - - if (!components.contains(message.compid)) - { - QString componentName; - - switch (message.compid) - { - case MAV_COMP_ID_ALL: - { - componentName = "ANONYMOUS"; - break; - } - case MAV_COMP_ID_IMU: - { - componentName = "IMU #1"; - break; - } - case MAV_COMP_ID_CAMERA: - { - componentName = "CAMERA"; - break; - } - case MAV_COMP_ID_MISSIONPLANNER: - { - componentName = "MISSIONPLANNER"; - break; - } - } - - components.insert(message.compid, componentName); - emit componentCreated(uasId, message.compid, componentName); - } - - // qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq; - - // Only accept messages from this system (condition 1) - // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled - // and we already got one attitude packet - if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE)) - { - QString uasState; - QString stateDescription; - - bool multiComponentSourceDetected = false; - bool wrongComponent = false; - - switch (message.compid) - { - case MAV_COMP_ID_IMU_2: - // Prefer IMU 2 over IMU 1 (FIXME) - componentID[message.msgid] = MAV_COMP_ID_IMU_2; - break; - default: - // Do nothing - break; - } - - // Store component ID - if (componentID[message.msgid] == -1) - { - // Prefer the first component - componentID[message.msgid] = message.compid; - } - else - { - // Got this message already - if (componentID[message.msgid] != message.compid) - { - componentMulti[message.msgid] = true; - wrongComponent = true; - } - } - - if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true; - - - switch (message.msgid) - { - case MAVLINK_MSG_ID_HEARTBEAT: - { - if (multiComponentSourceDetected && wrongComponent) - { - break; - } - lastHeartbeat = QGC::groundTimeUsecs(); - emit heartbeat(this); - mavlink_heartbeat_t state; - mavlink_msg_heartbeat_decode(&message, &state); - - // Send the base_mode and system_status values to the plotter. This uses the ground time - // so the Ground Time checkbox must be ticked for these values to display - quint64 time = getUnixTime(); - QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid); - emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time); - emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time); - emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time); - - // Set new type if it has changed - if (this->type != state.type) - { - this->type = state.type; - if (airframe == 0) - { - switch (type) - { - case MAV_TYPE_FIXED_WING: - setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR); - break; - case MAV_TYPE_QUADROTOR: - setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH); - break; - case MAV_TYPE_HEXAROTOR: - setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER); - break; - default: - // Do nothing - break; - } - } - this->autopilot = state.autopilot; - emit systemTypeSet(this, type); - } - - bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY; - - if (systemIsArmed != currentlyArmed) - { - systemIsArmed = currentlyArmed; - emit armingChanged(systemIsArmed); - if (systemIsArmed) - { - emit armed(); - } - else - { - emit disarmed(); - } - } - - QString audiostring = QString("System %1").arg(uasId); - QString stateAudio = ""; - QString modeAudio = ""; - QString navModeAudio = ""; - bool statechanged = false; - bool modechanged = false; - - QString audiomodeText = getAudioModeTextFor(static_cast(state.base_mode)); - - - if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT) - { - statechanged = true; - this->status = state.system_status; - getStatusForCode((int)state.system_status, uasState, stateDescription); - emit statusChanged(this, uasState, stateDescription); - emit statusChanged(this->status); - - shortStateText = uasState; - - // Adjust for better audio - if (uasState == QString("STANDBY")) uasState = QString("standing by"); - if (uasState == QString("EMERGENCY")) uasState = QString("emergency condition"); - if (uasState == QString("CRITICAL")) uasState = QString("critical condition"); - if (uasState == QString("SHUTDOWN")) uasState = QString("shutting down"); - - stateAudio = uasState; - } - - if (this->mode != static_cast(state.base_mode)) - { - modechanged = true; - this->mode = static_cast(state.base_mode); - shortModeText = getShortModeTextFor(this->mode); - - emit modeChanged(this->getUASID(), shortModeText, ""); - - modeAudio = " is now in " + audiomodeText; - } - - if (navMode != state.custom_mode) - { - emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode)); - navMode = state.custom_mode; - //navModeAudio = tr(" changed nav mode to ") + tr("FIXME"); - } - - // AUDIO - if (modechanged && statechanged) - { - // Output both messages - audiostring += modeAudio + " and " + stateAudio; - } - else if (modechanged || statechanged) - { - // Output the one message - audiostring += modeAudio + stateAudio + navModeAudio; - } - - if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)) - { - GAudioOutput::instance()->say(QString("emergency for system %1").arg(this->getUASID())); - QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency())); - } - else if (modechanged || statechanged) - { - GAudioOutput::instance()->stopEmergency(); - GAudioOutput::instance()->say(audiostring.toLower()); - } - } - - break; - case MAVLINK_MSG_ID_SYS_STATUS: - { - if (multiComponentSourceDetected && wrongComponent) - { - break; - } - mavlink_sys_status_t state; - mavlink_msg_sys_status_decode(&message, &state); - - // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present. - quint64 time = getUnixTime(); - QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid); - emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time); - emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time); - emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time); - emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time); - emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time); - emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time); - emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time); - - // Process CPU load. - emit loadChanged(this,state.load/10.0f); - emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time); - - // Battery charge/time remaining/voltage calculations - currentVoltage = state.voltage_battery/1000.0f; - lpVoltage = filterVoltage(currentVoltage); - tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage; - - - // We don't want to tick above the threshold - if (tickLowpassVoltage > tickVoltage) - { - lastTickVoltageValue = tickLowpassVoltage; - } - - if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f) - /* warn if lower than treshold */ - && (lpVoltage < tickVoltage) - /* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */ - && (currentVoltage > 3.3f) - /* warn only if current voltage is really still lower by a reasonable amount */ - && ((currentVoltage - 0.2f) < tickVoltage) - /* warn only every 12 seconds */ - && (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000) - { - GAudioOutput::instance()->say(QString("voltage warning: %1 volts").arg(lpVoltage, 0, 'f', 1, QChar(' '))); - lastVoltageWarning = QGC::groundTimeUsecs(); - lastTickVoltageValue = tickLowpassVoltage; - } - - if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage; - timeRemaining = calculateTimeRemaining(); - if (!batteryRemainingEstimateEnabled && chargeLevel != -1) - { - chargeLevel = state.battery_remaining; - } - emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining); - emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time); - emit voltageChanged(message.sysid, currentVoltage); - emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time); - - // And if the battery current draw is measured, log that also. - if (state.current_battery != -1) - { - emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time); - } - - // LOW BATTERY ALARM - if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3)) - { - startLowBattAlarm(); - } - else - { - stopLowBattAlarm(); - } - - // control_sensors_enabled: - // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control - emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11)); - emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12)); - emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13)); - emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14)); - - // Trigger drop rate updates as needed. Here we convert the incoming - // drop_rate_comm value from 1/100 of a percent in a uint16 to a true - // percentage as a float. We also cap the incoming value at 100% as defined - // by the MAVLink specifications. - if (state.drop_rate_comm > 10000) - { - state.drop_rate_comm = 10000; - } - emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f); - emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time); - } - break; - case MAVLINK_MSG_ID_ATTITUDE: - { - mavlink_attitude_t attitude; - mavlink_msg_attitude_decode(&message, &attitude); - quint64 time = getUnixReferenceTime(attitude.time_boot_ms); - - emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time); - - if (!wrongComponent) - { - lastAttitude = time; - roll = QGC::limitAngleToPMPIf(attitude.roll); - pitch = QGC::limitAngleToPMPIf(attitude.pitch); - yaw = QGC::limitAngleToPMPIf(attitude.yaw); - - // // Emit in angles - - // // Convert yaw angle to compass value - // // in 0 - 360 deg range - // float compass = (yaw/M_PI)*180.0+360.0f; - // if (compass > -10000 && compass < 10000) - // { - // while (compass > 360.0f) { - // compass -= 360.0f; - // } - // } - // else - // { - // // Set to 0, since it is an invalid value - // compass = 0.0f; - // } - - attitudeKnown = true; - emit attitudeChanged(this, roll, pitch, yaw, time); - emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); - } - } - break; - case MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET: - { - mavlink_local_position_ned_system_global_offset_t offset; - mavlink_msg_local_position_ned_system_global_offset_decode(&message, &offset); - nedPosGlobalOffset.setX(offset.x); - nedPosGlobalOffset.setY(offset.y); - nedPosGlobalOffset.setZ(offset.z); - nedAttGlobalOffset.setX(offset.roll); - nedAttGlobalOffset.setY(offset.pitch); - nedAttGlobalOffset.setZ(offset.yaw); - } - break; - case MAVLINK_MSG_ID_HIL_CONTROLS: - { - mavlink_hil_controls_t hil; - mavlink_msg_hil_controls_decode(&message, &hil); - emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode); - } - break; - case MAVLINK_MSG_ID_VFR_HUD: - { - mavlink_vfr_hud_t hud; - mavlink_msg_vfr_hud_decode(&message, &hud); - quint64 time = getUnixTime(); - // Display updated values - emit thrustChanged(this, hud.throttle/100.0); - - if (!attitudeKnown) - { - yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI); - emit attitudeChanged(this, roll, pitch, yaw, time); - } - - emit altitudeChanged(uasId, hud.alt); - emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time); - } - break; - case MAVLINK_MSG_ID_LOCAL_POSITION_NED: - //std::cerr << std::endl; - //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; - { - mavlink_local_position_ned_t pos; - mavlink_msg_local_position_ned_decode(&message, &pos); - quint64 time = getUnixTime(pos.time_boot_ms); - - // Emit position always with component ID - emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); - - - if (!wrongComponent) - { - localX = pos.x; - localY = pos.y; - localZ = pos.z; - - // Emit - - emit localPositionChanged(this, pos.x, pos.y, pos.z, time); - emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); - - // Set internal state - if (!positionLock) { - // If position was not locked before, notify positive - GAudioOutput::instance()->notifyPositive(); - } - positionLock = true; - isLocalPositionKnown = true; - } - } - break; - case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE: - { - mavlink_global_vision_position_estimate_t pos; - mavlink_msg_global_vision_position_estimate_decode(&message, &pos); - quint64 time = getUnixTime(pos.usec); - emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); - emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time); - } - break; - case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: - //std::cerr << std::endl; - //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; - { - mavlink_global_position_int_t pos; - mavlink_msg_global_position_int_decode(&message, &pos); - quint64 time = getUnixTime(); - latitude = pos.lat/(double)1E7; - longitude = pos.lon/(double)1E7; - altitude = pos.alt/1000.0; - speedX = pos.vx/100.0; - speedY = pos.vy/100.0; - speedZ = pos.vz/100.0; - emit globalPositionChanged(this, latitude, longitude, altitude, time); - emit speedChanged(this, speedX, speedY, speedZ, time); - - // Set internal state - if (!positionLock) - { - // If position was not locked before, notify positive - GAudioOutput::instance()->notifyPositive(); - } - positionLock = true; - isGlobalPositionKnown = true; - //TODO fix this hack for forwarding of global position for patch antenna tracking - forwardMessage(message); - } - break; - case MAVLINK_MSG_ID_GPS_RAW_INT: - { - mavlink_gps_raw_int_t pos; - mavlink_msg_gps_raw_int_decode(&message, &pos); - - // SANITY CHECK - // only accept values in a realistic range - // quint64 time = getUnixTime(pos.time_usec); - quint64 time = getUnixTime(pos.time_usec); - - emit gpsLocalizationChanged(this, pos.fix_type); - // TODO: track localization state not only for gps but also for other loc. sources - int loc_type = pos.fix_type; - if (loc_type == 1) - { - loc_type = 0; - } - emit localizationChanged(this, loc_type); - - if (pos.fix_type > 2) - { - emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time); - latitude = pos.lat/(double)1E7; - longitude = pos.lon/(double)1E7; - altitude = pos.alt/1000.0; - positionLock = true; - isGlobalPositionKnown = true; - - // Check for NaN - int alt = pos.alt; - if (!isnan(alt) && !isinf(alt)) - { - alt = 0; - //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE"); - } - // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time); - // Smaller than threshold and not NaN - - float vel = pos.vel/100.0f; - - if (vel < 1000000 && !isnan(vel) && !isinf(vel)) - { - // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time); - //qDebug() << "GOT GPS RAW"; - // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); - } - else - { - emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel)); - } - } - } - break; - case MAVLINK_MSG_ID_GPS_STATUS: - { - mavlink_gps_status_t pos; - mavlink_msg_gps_status_decode(&message, &pos); - for(int i = 0; i < (int)pos.satellites_visible; i++) - { - emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast(pos.satellite_used[i])); - } - } - break; - case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: - { - mavlink_gps_global_origin_t pos; - mavlink_msg_gps_global_origin_decode(&message, &pos); - emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0); - } - break; - case MAVLINK_MSG_ID_RC_CHANNELS_RAW: - { - mavlink_rc_channels_raw_t channels; - mavlink_msg_rc_channels_raw_decode(&message, &channels); - emit remoteControlRSSIChanged(channels.rssi/255.0f); - emit remoteControlChannelRawChanged(0, channels.chan1_raw); - emit remoteControlChannelRawChanged(1, channels.chan2_raw); - emit remoteControlChannelRawChanged(2, channels.chan3_raw); - emit remoteControlChannelRawChanged(3, channels.chan4_raw); - emit remoteControlChannelRawChanged(4, channels.chan5_raw); - emit remoteControlChannelRawChanged(5, channels.chan6_raw); - emit remoteControlChannelRawChanged(6, channels.chan7_raw); - emit remoteControlChannelRawChanged(7, channels.chan8_raw); - } - break; - case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: - { - mavlink_rc_channels_scaled_t channels; - mavlink_msg_rc_channels_scaled_decode(&message, &channels); - emit remoteControlRSSIChanged(channels.rssi/255.0f); - emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f); - emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f); - emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f); - emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f); - emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f); - emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f); - emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f); - emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f); - } - break; - case MAVLINK_MSG_ID_PARAM_VALUE: - { - mavlink_param_value_t value; - mavlink_msg_param_value_decode(&message, &value); - QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); - // Construct a string stopping at the first NUL (0) character, else copy the whole - // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe) - QString parameterName(bytes); - int component = message.compid; - mavlink_param_union_t val; - val.param_float = value.param_value; - val.type = value.param_type; - - // Insert component if necessary - if (!parameters.contains(component)) - { - parameters.insert(component, new QMap()); - } - - // Insert parameter into registry - if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName); - - // Insert with correct type - switch (value.param_type) - { - case MAV_PARAM_TYPE_REAL32: - { - // Variant - QVariant param(val.param_float); - parameters.value(component)->insert(parameterName, param); - // Emit change - emit parameterChanged(uasId, message.compid, parameterName, param); - emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); -// qDebug() << "RECEIVED PARAM:" << param; - } - break; - case MAV_PARAM_TYPE_UINT32: - { - // Variant - QVariant param(val.param_uint32); - parameters.value(component)->insert(parameterName, param); - // Emit change - emit parameterChanged(uasId, message.compid, parameterName, param); - emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); -// qDebug() << "RECEIVED PARAM:" << param; - } - break; - case MAV_PARAM_TYPE_INT32: - { - // Variant - QVariant param(val.param_int32); - parameters.value(component)->insert(parameterName, param); - // Emit change - emit parameterChanged(uasId, message.compid, parameterName, param); - emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); -// qDebug() << "RECEIVED PARAM:" << param; - } - break; - default: - qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type; - } - } - break; - case MAVLINK_MSG_ID_COMMAND_ACK: - { - mavlink_command_ack_t ack; - mavlink_msg_command_ack_decode(&message, &ack); - switch (ack.result) - { - case MAV_RESULT_ACCEPTED: - { - emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command)); - } - break; - case MAV_RESULT_TEMPORARILY_REJECTED: - { - emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command)); - } - break; - case MAV_RESULT_DENIED: - { - emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command)); - } - break; - case MAV_RESULT_UNSUPPORTED: - { - emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command)); - } - break; - case MAV_RESULT_FAILED: - { - emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command)); - } - break; - } - } - case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT: - { - mavlink_roll_pitch_yaw_thrust_setpoint_t out; - mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out); - quint64 time = getUnixTimeFromMs(out.time_boot_ms); - emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time); - } - break; - case MAVLINK_MSG_ID_MISSION_COUNT: - { - mavlink_mission_count_t wpc; - mavlink_msg_mission_count_decode(&message, &wpc); - if(wpc.target_system == mavlink->getSystemId() || wpc.target_system == 0) - { - waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count); - } - else - { - qDebug() << "Got waypoint message, but was wrong system id" << wpc.target_system; - } - } - break; - - case MAVLINK_MSG_ID_MISSION_ITEM: - { - mavlink_mission_item_t wp; - mavlink_msg_mission_item_decode(&message, &wp); - //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z; - if(wp.target_system == mavlink->getSystemId() || wp.target_system == 0) - { - waypointManager.handleWaypoint(message.sysid, message.compid, &wp); - } - else - { - qDebug() << "Got waypoint message, but was wrong system id" << wp.target_system; - } - } - break; - - case MAVLINK_MSG_ID_MISSION_ACK: - { - mavlink_mission_ack_t wpa; - mavlink_msg_mission_ack_decode(&message, &wpa); - if((wpa.target_system == mavlink->getSystemId() || wpa.target_system == 0) && - (wpa.target_component == mavlink->getComponentId() || wpa.target_component == 0)) - { - waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa); - } - } - break; - - case MAVLINK_MSG_ID_MISSION_REQUEST: - { - mavlink_mission_request_t wpr; - mavlink_msg_mission_request_decode(&message, &wpr); - if(wpr.target_system == mavlink->getSystemId() || wpr.target_system == 0) - { - waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr); - } - else - { - qDebug() << "Got waypoint message, but was wrong system id" << wpr.target_system; - } - } - break; - - case MAVLINK_MSG_ID_MISSION_ITEM_REACHED: - { - mavlink_mission_item_reached_t wpr; - mavlink_msg_mission_item_reached_decode(&message, &wpr); - waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr); - QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq); - GAudioOutput::instance()->say(text); - emit textMessageReceived(message.sysid, message.compid, 0, text); - } - break; - - case MAVLINK_MSG_ID_MISSION_CURRENT: - { - mavlink_mission_current_t wpc; - mavlink_msg_mission_current_decode(&message, &wpc); - waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc); - } - break; - - case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT: - { - if (multiComponentSourceDetected && wrongComponent) - { - break; - } - mavlink_local_position_setpoint_t p; - mavlink_msg_local_position_setpoint_decode(&message, &p); - emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs()); - } - break; - case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT: - { - mavlink_set_local_position_setpoint_t p; - mavlink_msg_set_local_position_setpoint_decode(&message, &p); - emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw); - } - break; - case MAVLINK_MSG_ID_STATUSTEXT: - { - QByteArray b; - b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN); - mavlink_msg_statustext_get_text(&message, b.data()); - //b.append('\0'); - QString text = QString(b); - int severity = mavlink_msg_statustext_get_severity(&message); - //qDebug() << "RECEIVED STATUS:" << text;false - //emit statusTextReceived(severity, text); - - if (text.startsWith("#audio:")) - { - text.remove("#audio:"); - emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text); - GAudioOutput::instance()->say(text, severity); - } - else - { - emit textMessageReceived(uasId, message.compid, severity, text); - } - } - break; - case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW: - { - mavlink_servo_output_raw_t raw; - mavlink_msg_servo_output_raw_decode(&message, &raw); - - if (hilEnabled) - { - emit hilActuatorsChanged(static_cast(getUnixTimeFromMs(raw.time_boot_ms)), static_cast(raw.servo1_raw), - static_cast(raw.servo2_raw), static_cast(raw.servo3_raw), - static_cast(raw.servo4_raw), static_cast(raw.servo5_raw), static_cast(raw.servo6_raw), - static_cast(raw.servo7_raw), static_cast(raw.servo8_raw)); - } - } - break; -#ifdef MAVLINK_ENABLED_PIXHAWK - case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE: - { - mavlink_data_transmission_handshake_t p; - mavlink_msg_data_transmission_handshake_decode(&message, &p); - imageSize = p.size; - imagePackets = p.packets; - imagePayload = p.payload; - imageQuality = p.jpg_quality; - imageType = p.type; - imageWidth = p.width; - imageHeight = p.height; - imageStart = QGC::groundTimeMilliseconds(); - } - break; - - case MAVLINK_MSG_ID_ENCAPSULATED_DATA: - { - mavlink_encapsulated_data_t img; - mavlink_msg_encapsulated_data_decode(&message, &img); - int seq = img.seqnr; - int pos = seq * imagePayload; - - // Check if we have a valid transaction - if (imagePackets == 0) - { - // NO VALID TRANSACTION - ABORT - // Restart statemachine - imagePacketsArrived = 0; - } - - for (int i = 0; i < imagePayload; ++i) - { - if (pos <= imageSize) { - imageRecBuffer[pos] = img.data[i]; - } - ++pos; - } - - ++imagePacketsArrived; - - // emit signal if all packets arrived - if ((imagePacketsArrived >= imagePackets)) - { - // Restart statemachine - imagePacketsArrived = 0; - emit imageReady(this); - //qDebug() << "imageReady emitted. all packets arrived"; - } - } - break; - - - -#endif - // case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT: - // { - // mavlink_object_detection_event_t event; - // mavlink_msg_object_detection_event_decode(&message, &event); - // QString str(event.name); - // emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance); - // } - // break; - // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET - // case MAVLINK_MSG_ID_MEMORY_VECT: - // { - // mavlink_memory_vect_t vect; - // mavlink_msg_memory_vect_decode(&message, &vect); - // QString str("mem_%1"); - // quint64 time = getUnixTime(0); - // int16_t *mem0 = (int16_t *)&vect.value[0]; - // uint16_t *mem1 = (uint16_t *)&vect.value[0]; - // int32_t *mem2 = (int32_t *)&vect.value[0]; - // // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem - // float *mem4 = (float *)&vect.value[0]; - // if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ; - // if ( vect.ver == 1) - // { - // switch (vect.type) { - // default: - // case 0: - // for (int i = 0; i < 16; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time); - // break; - // case 1: - // for (int i = 0; i < 16; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time); - // break; - // case 2: - // for (int i = 0; i < 16; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time); - // break; - // case 3: - // for (int i = 0; i < 16; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time); - // break; - // case 4: - // for (int i = 0; i < 8; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); - // break; - // case 5: - // for (int i = 0; i < 8; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); - // break; - // case 6: - // for (int i = 0; i < 8; i++) - // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time); - // break; - // } - // } - // } - // break; -#ifdef MAVLINK_ENABLED_UALBERTA - case MAVLINK_MSG_ID_NAV_FILTER_BIAS: - { - mavlink_nav_filter_bias_t bias; - mavlink_msg_nav_filter_bias_decode(&message, &bias); - quint64 time = getUnixTime(); - // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time); - // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time); - // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time); - // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time); - // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time); - // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time); - } - break; - case MAVLINK_MSG_ID_RADIO_CALIBRATION: - { - mavlink_radio_calibration_t radioMsg; - mavlink_msg_radio_calibration_decode(&message, &radioMsg); - QVector aileron; - QVector elevator; - QVector rudder; - QVector gyro; - QVector pitch; - QVector throttle; - - for (int i=0; i radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle); - emit radioCalibrationReceived(radioData); - delete radioData; - } - break; - -#endif - // Messages to ignore - case MAVLINK_MSG_ID_RAW_IMU: - case MAVLINK_MSG_ID_SCALED_IMU: - case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: - case MAVLINK_MSG_ID_RAW_PRESSURE: - case MAVLINK_MSG_ID_SCALED_PRESSURE: - case MAVLINK_MSG_ID_OPTICAL_FLOW: - case MAVLINK_MSG_ID_DEBUG_VECT: - case MAVLINK_MSG_ID_DEBUG: - case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: - case MAVLINK_MSG_ID_NAMED_VALUE_INT: - case MAVLINK_MSG_ID_MANUAL_CONTROL: - case MAVLINK_MSG_ID_HIGHRES_IMU: - break; - default: - { - if (!unknownPackets.contains(message.msgid)) - { - unknownPackets.append(message.msgid); - QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid); - //GAudioOutput::instance()->say(errString+tr(", please check console for details.")); - emit textMessageReceived(uasId, message.compid, 255, errString); - std::cout << "Unable to decode message from system " << std::dec << static_cast(message.sysid) << " with message id:" << static_cast(message.msgid) << std::endl; - //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast(message.acid) << " with message id:" << static_cast(message.msgid) << std::endl; - } - } - break; - } - } -} - - -#if defined(QGC_PROTOBUF_ENABLED) -/** -* Receive an extended message. -* @param link -* @param message -*/ -void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr message) -{ - if (!link) - { - return; - } - if (!links->contains(link)) - { - addLink(link); - } - - const google::protobuf::Descriptor* descriptor = message->GetDescriptor(); - if (!descriptor) - { - return; - } - - const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header"); - if (!headerField) - { - return; - } - - const google::protobuf::Descriptor* headerDescriptor = headerField->message_type(); - if (!headerDescriptor) - { - return; - } - - const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid"); - if (!sourceSysIdField) - { - return; - } - - const google::protobuf::Reflection* reflection = message->GetReflection(); - const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField); - const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection(); - - int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField); - - if (source_sysid != uasId) - { - return; - } - -#ifdef QGC_USE_PIXHAWK_MESSAGES - if (message->GetTypeName() == overlay.GetTypeName()) - { - receivedOverlayTimestamp = QGC::groundTimeSeconds(); - overlayMutex.lock(); - overlay.CopyFrom(*message); - overlayMutex.unlock(); - emit overlayChanged(this); - } - else if (message->GetTypeName() == obstacleList.GetTypeName()) - { - receivedObstacleListTimestamp = QGC::groundTimeSeconds(); - obstacleListMutex.lock(); - obstacleList.CopyFrom(*message); - obstacleListMutex.unlock(); - emit obstacleListChanged(this); - } - else if (message->GetTypeName() == path.GetTypeName()) - { - receivedPathTimestamp = QGC::groundTimeSeconds(); - pathMutex.lock(); - path.CopyFrom(*message); - pathMutex.unlock(); - emit pathChanged(this); - } - else if (message->GetTypeName() == pointCloud.GetTypeName()) - { - receivedPointCloudTimestamp = QGC::groundTimeSeconds(); - pointCloudMutex.lock(); - pointCloud.CopyFrom(*message); - pointCloudMutex.unlock(); - emit pointCloudChanged(this); - } - else if (message->GetTypeName() == rgbdImage.GetTypeName()) - { - receivedRGBDImageTimestamp = QGC::groundTimeSeconds(); - rgbdImageMutex.lock(); - rgbdImage.CopyFrom(*message); - rgbdImageMutex.unlock(); - emit rgbdImageChanged(this); - } -#endif -} - -#endif - -/** -* Set the home position of the UAS. -* @param lat The latitude fo the home position -* @param lon The longitute of the home position -* @param alt The altitude of the home position -*/ -void UAS::setHomePosition(double lat, double lon, double alt) -{ - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Warning); - msgBox.setText("Setting new World Coordinate Frame Origin"); - msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location"); - msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); - msgBox.setDefaultButton(QMessageBox::Cancel); - int ret = msgBox.exec(); - - // Close the message box shortly after the click to prevent accidental clicks - QTimer::singleShot(5000, &msgBox, SLOT(reject())); - - - if (ret == QMessageBox::Yes) - { - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt); - // Send message twice to increase chance that it reaches its goal - sendMessage(msg); - - // Send new home position to UAS - mavlink_set_gps_global_origin_t home; - home.target_system = uasId; - home.latitude = lat*1E7; - home.longitude = lon*1E7; - home.altitude = alt*1000; - qDebug() << "lat:" << home.latitude << " lon:" << home.longitude; - mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home); - sendMessage(msg); - } -} - -/** -* Set the origin to the current GPS location. -**/ -void UAS::setLocalOriginAtCurrentGPSPosition() -{ - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Warning); - msgBox.setText("Setting new World Coordinate Frame Origin"); - msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location"); - msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); - msgBox.setDefaultButton(QMessageBox::Cancel); - int ret = msgBox.exec(); - - // Close the message box shortly after the click to prevent accidental clicks - QTimer::singleShot(5000, &msgBox, SLOT(reject())); - - - if (ret == QMessageBox::Yes) - { - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0); - // Send message twice to increase chance that it reaches its goal - sendMessage(msg); - } -} - -/** -* Set a local position setpoint. -* @param x postion -* @param y position -* @param z position -*/ -void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) -{ -#ifdef MAVLINK_ENABLED_PIXHAWK - mavlink_message_t msg; - mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0); - sendMessage(msg); -#else - Q_UNUSED(x); - Q_UNUSED(y); - Q_UNUSED(z); - Q_UNUSED(yaw); -#endif -} - -/** -* Set a offset of the local position. -* @param x position -* @param y position -* @param z position -* @param yaw -*/ -void UAS::setLocalPositionOffset(float x, float y, float z, float yaw) -{ -#ifdef MAVLINK_ENABLED_PIXHAWK - mavlink_message_t msg; - mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw); - sendMessage(msg); -#else - Q_UNUSED(x); - Q_UNUSED(y); - Q_UNUSED(z); - Q_UNUSED(yaw); -#endif -} - -void UAS::startRadioControlCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0); - sendMessage(msg); -} - -void UAS::startDataRecording() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0); - sendMessage(msg); -} - -void UAS::stopDataRecording() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0); - sendMessage(msg); -} - -void UAS::startMagnetometerCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -void UAS::startGyroscopeCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -void UAS::startPressureCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0); - sendMessage(msg); -} - -/** -* Check if time is smaller than 40 years, assuming no system without Unix -* timestamp runs longer than 40 years continuously without reboot. In worst case -* this will add/subtract the communication delay between GCS and MAV, it will -* never alter the timestamp in a safety critical way. -*/ -quint64 UAS::getUnixReferenceTime(quint64 time) -{ - // Same as getUnixTime, but does not react to attitudeStamped mode - if (time == 0) - { - // qDebug() << "XNEW time:" < has to be - // a Unix epoch timestamp. Do nothing. - return time/1000; - } -} - -/** -* @warning If attitudeStamped is enabled, this function will not actually return -* the precise time stamp of this measurement augmented to UNIX time, but will -* MOVE the timestamp IN TIME to match the last measured attitude. There is no -* reason why one would want this, except for system setups where the onboard -* clock is not present or broken and datasets should be collected that are still -* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE -* SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL! -*/ -quint64 UAS::getUnixTimeFromMs(quint64 time) -{ - return getUnixTime(time*1000); -} - -/** -* @warning If attitudeStamped is enabled, this function will not actually return -* the precise time stam of this measurement augmented to UNIX time, but will -* MOVE the timestamp IN TIME to match the last measured attitude. There is no -* reason why one would want this, except for system setups where the onboard -* clock is not present or broken and datasets should be collected that are -* still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED -* RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL! -*/ -quint64 UAS::getUnixTime(quint64 time) -{ - quint64 ret = 0; - if (attitudeStamped) - { - ret = lastAttitude; - } - - if (time == 0) - { - ret = QGC::groundTimeMilliseconds(); - } - // Check if time is smaller than 40 years, - // assuming no system without Unix timestamp - // runs longer than 40 years continuously without - // reboot. In worst case this will add/subtract the - // communication delay between GCS and MAV, - // it will never alter the timestamp in a safety - // critical way. - // - // Calculation: - // 40 years - // 365 days - // 24 hours - // 60 minutes - // 60 seconds - // 1000 milliseconds - // 1000 microseconds -#ifndef _MSC_VER - else if (time < 1261440000000000LLU) -#else - else if (time < 1261440000000000) -#endif - { - // qDebug() << "GEN time:" << time/1000 + onboardTimeOffset; - if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100)) - { - lastNonNullTime = time; - onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000; - } - if (time > lastNonNullTime) lastNonNullTime = time; - - ret = time/1000 + onboardTimeOffset; - } - else - { - // Time is not zero and larger than 40 years -> has to be - // a Unix epoch timestamp. Do nothing. - ret = time/1000; - } - - return ret; -} - -/** -* @param component that will be searched for in the map of parameters. -*/ -QList UAS::getParameterNames(int component) -{ - if (parameters.contains(component)) - { - return parameters.value(component)->keys(); - } - else - { - return QList(); - } -} - -QList UAS::getComponentIds() -{ - return parameters.keys(); -} - -/** -* @param mode that UAS is to be set to. -*/ -void UAS::setMode(int mode) -{ - //this->mode = mode; //no call assignament, update receive message from UAS - mavlink_message_t msg; - mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode); - sendMessage(msg); - qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode; -} - -/** -* Send a message to every link that is connected. -* @param message that is to be sent -*/ -void UAS::sendMessage(mavlink_message_t message) -{ - if (!LinkManager::instance()) return; - // Emit message on all links that are currently connected - foreach (LinkInterface* link, *links) - { - if (LinkManager::instance()->getLinks().contains(link)) - { - sendMessage(link, message); - } - else - { - // Remove from list - links->removeAt(links->indexOf(link)); - } - } -} - -/** -* Forward a message to all links that are currently connected. -* @param message that is to be forwarded -*/ -void UAS::forwardMessage(mavlink_message_t message) -{ - // Emit message on all links that are currently connected - QListlink_list = LinkManager::instance()->getLinksForProtocol(mavlink); - - foreach(LinkInterface* link, link_list) - { - if (link) - { - SerialLink* serial = dynamic_cast(link); - if(serial != 0) - { - for(int i=0; isize(); i++) - { - if(serial != links->at(i)) - { - qDebug()<<"Antenna tracking: Forwarding Over link: "<getName()<<" "<getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]); - // If link is connected - if (link->isConnected()) - { - // Send the portion of the buffer now occupied by the message - link->writeBytes((const char*)buffer, len); - } -} - -/** - * @param value battery voltage - */ -float UAS::filterVoltage(float value) const -{ - return lpVoltage * 0.7f + value * 0.3f; -} - -/** -* The mode can be preflight or unknown. -* @Return the mode of the autopilot -*/ -QString UAS::getNavModeText(int mode) -{ - if (autopilot == MAV_AUTOPILOT_PIXHAWK) - { - switch (mode) - { - case 0: - return QString("PREFLIGHT"); - break; - default: - return QString("UNKNOWN"); - } - } - else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) - { - return QString("UNKNOWN"); - } - else if (autopilot == MAV_AUTOPILOT_OPENPILOT) - { - return QString("UNKNOWN"); - } - // If nothing matches, return unknown - return QString("UNKNOWN"); -} - -/** -* Get the status of the code and a description of the status. -* Status can be unitialized, booting up, calibrating sensors, active -* standby, cirtical, emergency, shutdown or unknown. -*/ -void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription) -{ - switch (statusCode) - { - case MAV_STATE_UNINIT: - uasState = tr("UNINIT"); - stateDescription = tr("Unitialized, booting up."); - break; - case MAV_STATE_BOOT: - uasState = tr("BOOT"); - stateDescription = tr("Booting system, please wait."); - break; - case MAV_STATE_CALIBRATING: - uasState = tr("CALIBRATING"); - stateDescription = tr("Calibrating sensors, please wait."); - break; - case MAV_STATE_ACTIVE: - uasState = tr("ACTIVE"); - stateDescription = tr("Active, normal operation."); - break; - case MAV_STATE_STANDBY: - uasState = tr("STANDBY"); - stateDescription = tr("Standby mode, ready for launch."); - break; - case MAV_STATE_CRITICAL: - uasState = tr("CRITICAL"); - stateDescription = tr("FAILURE: Continuing operation."); - break; - case MAV_STATE_EMERGENCY: - uasState = tr("EMERGENCY"); - stateDescription = tr("EMERGENCY: Land Immediately!"); - break; - //case MAV_STATE_HILSIM: - //uasState = tr("HIL SIM"); - //stateDescription = tr("HIL Simulation, Sensors read from SIM"); - //break; - - case MAV_STATE_POWEROFF: - uasState = tr("SHUTDOWN"); - stateDescription = tr("Powering off system."); - break; - - default: - uasState = tr("UNKNOWN"); - stateDescription = tr("Unknown system state"); - break; - } -} - -QImage UAS::getImage() -{ -#ifdef MAVLINK_ENABLED_PIXHAWK - -// qDebug() << "IMAGE TYPE:" << imageType; - - // RAW greyscale - if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U) - { - // TODO FIXME - int imgColors = 255;//imageSize/(imageWidth*imageHeight); - //const int headerSize = 15; - - // Construct PGM header - QString header("P5\n%1 %2\n%3\n"); - header = header.arg(imageWidth).arg(imageHeight).arg(imgColors); - - QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size()); - tmpImage.append(imageRecBuffer); - - //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header; - - if (imageRecBuffer.isNull()) - { - qDebug()<< "could not convertToPGM()"; - return QImage(); - } - - if (!image.loadFromData(tmpImage, "PGM")) - { - qDebug()<< "could not create extracted image"; - return QImage(); - } - - } - // BMP with header - else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP || - imageType == MAVLINK_DATA_STREAM_IMG_JPEG || - imageType == MAVLINK_DATA_STREAM_IMG_PGM || - imageType == MAVLINK_DATA_STREAM_IMG_PNG) - { - if (!image.loadFromData(imageRecBuffer)) - { - qDebug() << "Loading data from image buffer failed!"; - } - } - // Restart statemachine - imagePacketsArrived = 0; - //imageRecBuffer.clear(); - return image; -#else - return QImage(); -#endif - -} - -void UAS::requestImage() -{ -#ifdef MAVLINK_ENABLED_PIXHAWK - qDebug() << "trying to get an image from the uas..."; - - // check if there is already an image transmission going on - if (imagePacketsArrived == 0) - { - mavlink_message_t msg; - mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50); - sendMessage(msg); - } -#endif -} - - -/* MANAGEMENT */ - -/** - * - * @return The uptime in milliseconds - * - */ -quint64 UAS::getUptime() const -{ - if(startTime == 0) - { - return 0; - } - else - { - return QGC::groundTimeMilliseconds() - startTime; - } -} - -int UAS::getCommunicationStatus() const -{ - return commStatus; -} - -void UAS::requestParameters() -{ - mavlink_message_t msg; - mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL); - sendMessage(msg); - qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST"; -} - -void UAS::writeParametersToStorage() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); - qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE; - sendMessage(msg); -} - -void UAS::readParametersFromStorage() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0); - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableAllDataTransmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - // 0 is a magic ID and will enable/disable the standard message set except for heartbeat - stream.req_stream_id = MAV_DATA_STREAM_ALL; - // Select the update rate in Hz the message should be send - // All messages will be send with their default rate - // TODO: use 0 to turn off and get rid of enable/disable? will require - // a different magic flag for turning on defaults, possibly something really high like 1111 ? - stream.req_message_rate = 0; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableRawSensorDataTransmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableExtendedSystemStatusTransmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableRCChannelDataTransmission(int rate) -{ -#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES) - mavlink_message_t msg; - mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled); - sendMessage(msg); -#else - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); -#endif -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableRawControllerDataTransmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); -} - -//void UAS::enableRawSensorFusionTransmission(int rate) -//{ -// // Buffers to write data to -// mavlink_message_t msg; -// mavlink_request_data_stream_t stream; -// // Select the message to request from now on -// stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION; -// // Select the update rate in Hz the message should be send -// stream.req_message_rate = rate; -// // Start / stop the message -// stream.start_stop = (rate) ? 1 : 0; -// // The system which should take this command -// stream.target_system = uasId; -// // The component / subsystem which should take this command -// stream.target_component = 0; -// // Encode and send the message -// mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); -// // Send message twice to increase chance of reception -// sendMessage(msg); -// sendMessage(msg); -//} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enablePositionTransmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_POSITION; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableExtra1Transmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_EXTRA1; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableExtra2Transmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_EXTRA2; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); - sendMessage(msg); -} - -/** -* @param rate The update rate in Hz the message should be sent -*/ -void UAS::enableExtra3Transmission(int rate) -{ - // Buffers to write data to - mavlink_message_t msg; - mavlink_request_data_stream_t stream; - // Select the message to request from now on - stream.req_stream_id = MAV_DATA_STREAM_EXTRA3; - // Select the update rate in Hz the message should be send - stream.req_message_rate = rate; - // Start / stop the message - stream.start_stop = (rate) ? 1 : 0; - // The system which should take this command - stream.target_system = uasId; - // The component / subsystem which should take this command - stream.target_component = 0; - // Encode and send the message - mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); - // Send message twice to increase chance of reception - sendMessage(msg); - sendMessage(msg); -} - -/** - * Set a parameter value onboard - * - * @param component The component to set the parameter - * @param id Name of the parameter - */ -void UAS::setParameter(const int component, const QString& id, const QVariant& value) -{ - if (!id.isNull()) - { - mavlink_message_t msg; - mavlink_param_set_t p; - mavlink_param_union_t union_value; - - // Assign correct value based on QVariant - switch (value.type()) - { - case QVariant::Int: - union_value.param_int32 = value.toInt(); - p.param_type = MAV_PARAM_TYPE_INT32; - break; - case QVariant::UInt: - union_value.param_uint32 = value.toUInt(); - p.param_type = MAV_PARAM_TYPE_UINT32; - break; - case QMetaType::Float: - union_value.param_float = value.toFloat(); - p.param_type = MAV_PARAM_TYPE_REAL32; - break; - default: - qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE"; - return; - } - - p.param_value = union_value.param_float; - p.target_system = (uint8_t)uasId; - p.target_component = (uint8_t)component; - - //qDebug() << "SENT PARAM:" << value; - - // Copy string into buffer, ensuring not to exceed the buffer size - for (unsigned int i = 0; i < sizeof(p.param_id); i++) - { - // String characters - if ((int)i < id.length()) - { - p.param_id[i] = id.toAscii()[i]; - } - else - { - // Fill rest with zeros - p.param_id[i] = 0; - } - } - mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p); - sendMessage(msg); - } -} - -/** -* Request parameter, use parameter name to request it. -*/ -void UAS::requestParameter(int component, int id) -{ - // Request parameter, use parameter name to request it - mavlink_message_t msg; - mavlink_param_request_read_t read; - read.param_index = id; - read.param_id[0] = '\0'; // Enforce null termination - read.target_system = uasId; - read.target_component = component; - mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read); - sendMessage(msg); - //qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id; -} - -/** -* Request a parameter, use parameter name to request it. -*/ -void UAS::requestParameter(int component, const QString& parameter) -{ - // Request parameter, use parameter name to request it - mavlink_message_t msg; - mavlink_param_request_read_t read; - read.param_index = -1; - // Copy full param name or maximum max field size - if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN) - { - emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1)); - } - memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)); - read.param_id[15] = '\0'; // Enforce null termination - read.target_system = uasId; - read.target_component = component; - mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read); - sendMessage(msg); - qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter; -} - -/** -* @param systemType Type of MAV. -*/ -void UAS::setSystemType(int systemType) -{ - if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END)) - { - type = systemType; - - // If the airframe is still generic, change it to a close default type - if (airframe == 0) - { - switch (systemType) - { - case MAV_TYPE_FIXED_WING: - airframe = QGC_AIRFRAME_EASYSTAR; - break; - case MAV_TYPE_QUADROTOR: - airframe = QGC_AIRFRAME_MIKROKOPTER; - break; - } - } - emit systemSpecsChanged(uasId); - } -} - -void UAS::setUASName(const QString& name) -{ - if (name != "") - { - this->name = name; - writeSettings(); - emit nameChanged(name); - emit systemSpecsChanged(uasId); - } -} - -void UAS::executeCommand(MAV_CMD command) -{ - mavlink_message_t msg; - mavlink_command_long_t cmd; - cmd.command = (uint16_t)command; - cmd.confirmation = 0; - cmd.param1 = 0.0f; - cmd.param2 = 0.0f; - cmd.param3 = 0.0f; - cmd.param4 = 0.0f; - cmd.param5 = 0.0f; - cmd.param6 = 0.0f; - cmd.param7 = 0.0f; - cmd.target_system = uasId; - cmd.target_component = 0; - mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); - sendMessage(msg); -} - -void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) -{ - mavlink_message_t msg; - mavlink_command_long_t cmd; - cmd.command = (uint16_t)command; - cmd.confirmation = confirmation; - cmd.param1 = param1; - cmd.param2 = param2; - cmd.param3 = param3; - cmd.param4 = param4; - cmd.param5 = param5; - cmd.param6 = param6; - cmd.param7 = param7; - cmd.target_system = uasId; - cmd.target_component = component; - mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); - sendMessage(msg); -} - -/** - * Launches the system - * - */ -void UAS::launch() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -/** - * @warning Depending on the UAS, this might make the rotors of a helicopter spinning - * - */ -void UAS::armSystem() -{ - mavlink_message_t msg; - mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_SAFETY_ARMED, navMode); - sendMessage(msg); -} - -/** - * @warning Depending on the UAS, this might completely stop all motors. - * - */ -void UAS::disarmSystem() -{ - mavlink_message_t msg; - mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & ~MAV_MODE_FLAG_SAFETY_ARMED, navMode); - sendMessage(msg); -} - -/** -* Set the manual control commands. -* This can only be done if the system has manual inputs enabled and is armed. -*/ -void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons) -{ - // Scale values - double rollPitchScaling = 1.0f * 1000.0f; - double yawScaling = 1.0f * 1000.0f; - double thrustScaling = 1.0f * 1000.0f; - - manualRollAngle = roll * rollPitchScaling; - manualPitchAngle = pitch * rollPitchScaling; - manualYawAngle = yaw * yawScaling; - manualThrust = thrust * thrustScaling; - - // If system has manual inputs enabled and is armed - if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED)) - { - mavlink_message_t message; - mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualPitchAngle, (float)manualRollAngle, (float)manualThrust, (float)manualYawAngle, buttons); - sendMessage(message); - //qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; - - emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds()); - } - else - { - qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first"; - } -} - -/** -* @return the type of the system -*/ -int UAS::getSystemType() -{ - return this->type; -} - -/** -* @param buttonIndex -*/ -void UAS::receiveButton(int buttonIndex) -{ - switch (buttonIndex) - { - case 0: - - break; - case 1: - - break; - default: - - break; - } - // qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!"; - -} - -/** -* Halt the uas. -*/ -void UAS::halt() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -/** -* Make the UAS move. -*/ -void UAS::go() -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -/** -* Order the robot to return home -*/ -void UAS::home() -{ - mavlink_message_t msg; - - double latitude = UASManager::instance()->getHomeLatitude(); - double longitude = UASManager::instance()->getHomeLongitude(); - double altitude = UASManager::instance()->getHomeAltitude(); - int frame = UASManager::instance()->getHomeFrame(); - - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude); - sendMessage(msg); -} - -/** -* Order the robot to land on the runway -*/ -void UAS::land() -{ - mavlink_message_t msg; - - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_LAND, 1, 0, 0, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -/** - * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation - * and might differ between systems. - */ -void UAS::emergencySTOP() -{ - // FIXME MAVLINKV10PORTINGNEEDED - halt(); -} - -/** - * Shut down this mav - All onboard systems are immediately shut down (e.g. the - * main power line is cut). - * @warning This might lead to a crash. - * - * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards - */ -bool UAS::emergencyKILL() -{ - halt(); - // FIXME MAVLINKV10PORTINGNEEDED - // bool result = false; - // QMessageBox msgBox; - // msgBox.setIcon(QMessageBox::Critical); - // msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS"); - // msgBox.setInformativeText("Do you want to cut power on all systems?"); - // msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); - // msgBox.setDefaultButton(QMessageBox::Cancel); - // int ret = msgBox.exec(); - - // // Close the message box shortly after the click to prevent accidental clicks - // QTimer::singleShot(5000, &msgBox, SLOT(reject())); - - - // if (ret == QMessageBox::Yes) - // { - // mavlink_message_t msg; - // // TODO Replace MG System ID with static function call and allow to change ID in GUI - // mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL); - // // Send message twice to increase chance of reception - // sendMessage(msg); - // sendMessage(msg); - // result = true; - // } - // return result; - return false; -} - -/** -* If enabled, connect the flight gear link. -*/ -void UAS::enableHilFlightGear(bool enable, QString options) -{ - QGCFlightGearLink* link = dynamic_cast(simulation); - if (!link || !simulation) { - // Delete wrong sim - if (simulation) { - stopHil(); - delete simulation; - } - simulation = new QGCFlightGearLink(this, options); - } - // Connect Flight Gear Link - link = dynamic_cast(simulation); - link->setStartupArguments(options); - if (enable) - { - startHil(); - } - else - { - stopHil(); - } -} - -/** -* If enabled, connect the X-plane gear link. -*/ -void UAS::enableHilXPlane(bool enable) -{ - QGCXPlaneLink* link = dynamic_cast(simulation); - if (!link || !simulation) { - if (simulation) { - stopHil(); - delete simulation; - } - qDebug() << "CREATED NEW XPLANE LINK"; - simulation = new QGCXPlaneLink(this); - } - // Connect X-Plane Link - if (enable) - { - startHil(); - } - else - { - stopHil(); - } -} - -/** -* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot) -* @param roll Roll angle (rad) -* @param pitch Pitch angle (rad) -* @param yaw Yaw angle (rad) -* @param rollspeed Roll angular speed (rad/s) -* @param pitchspeed Pitch angular speed (rad/s) -* @param yawspeed Yaw angular speed (rad/s) -* @param lat Latitude, expressed as * 1E7 -* @param lon Longitude, expressed as * 1E7 -* @param alt Altitude in meters, expressed as * 1000 (millimeters) -* @param vx Ground X Speed (Latitude), expressed as m/s * 100 -* @param vy Ground Y Speed (Longitude), expressed as m/s * 100 -* @param vz Ground Z Speed (Altitude), expressed as m/s * 100 -* @param xacc X acceleration (mg) -* @param yacc Y acceleration (mg) -* @param zacc Z acceleration (mg) -*/ -void UAS::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) -{ - if (this->mode & MAV_MODE_FLAG_HIL_ENABLED) - { - mavlink_message_t msg; - mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, - time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, - lat, lon, alt, vx, vy, vz, xacc, yacc, zacc); - sendMessage(msg); - } - else - { - // Attempt to set HIL mode - mavlink_message_t msg; - mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode); - sendMessage(msg); - qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable."; - } -} - -/** -* Connect flight gear link. -**/ -void UAS::startHil() -{ - if (hilEnabled) return; - hilEnabled = true; - // Connect HIL simulation link - simulation->connectSimulation(); - mavlink_message_t msg; - mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode); - sendMessage(msg); -} - -/** -* disable flight gear link. -*/ -void UAS::stopHil() -{ - if (simulation) simulation->disconnectSimulation(); - mavlink_message_t msg; - mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode); - sendMessage(msg); - hilEnabled = false; -} - -void UAS::shutdown() -{ - bool result = false; - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText("Shutting down the UAS"); - msgBox.setInformativeText("Do you want to shut down the onboard computer?"); - - msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); - msgBox.setDefaultButton(QMessageBox::Cancel); - int ret = msgBox.exec(); - - // Close the message box shortly after the click to prevent accidental clicks - QTimer::singleShot(5000, &msgBox, SLOT(reject())); - - if (ret == QMessageBox::Yes) - { - // If the active UAS is set, execute command - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0); - sendMessage(msg); - result = true; - } -} - -/** -* @param x position -* @param y position -* @param z position -* @param yaw -*/ -void UAS::setTargetPosition(float x, float y, float z, float yaw) -{ - mavlink_message_t msg; - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 1, 0, yaw, x, y, z); - sendMessage(msg); -} - -/** - * @return The name of this system as string in human-readable form - */ -QString UAS::getUASName(void) const -{ - QString result; - if (name == "") - { - result = tr("MAV ") + result.sprintf("%03d", getUASID()); - } - else - { - result = name; - } - return result; -} - -/** -* @return the state of the uas as a short text. -*/ -const QString& UAS::getShortState() const -{ - return shortStateText; -} - -/** -* The mode can be autonomous, guided, manual or armed. It will also return if -* hardware in the loop is being used. -* @return the audio mode text for the id given. -*/ -QString UAS::getAudioModeTextFor(int id) -{ - QString mode; - uint8_t modeid = id; - - // BASE MODE DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) - { - mode += "autonomous"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) - { - mode += "guided"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) - { - mode += "manual"; - } - else - { - // Nothing else applies, we're in preflight - mode += "preflight"; - } - - if (modeid != 0) - { - mode += " mode"; - } - - // ARMED STATE DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) - { - mode.append(" and armed"); - } - - // HARDWARE IN THE LOOP DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL) - { - mode.append(" using hardware in the loop simulation"); - } - - return mode; -} - -/** -* The mode returned can be auto, stabilized, test, manual, preflight or unknown. -* @return the short text of the mode for the id given. -*/ -QString UAS::getShortModeTextFor(int id) -{ - QString mode; - uint8_t modeid = id; - - qDebug() << "MODE:" << modeid; - - // BASE MODE DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) - { - mode += "AUTO"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) - { - mode += "|STABILIZED"; - } -// if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) -// { -// mode += "|STAB"; -// } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST) - { - mode += "|TEST"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) - { - mode += "|MANUAL"; - } - else if (modeid == 0) - { - mode = "|PREFLIGHT"; - } - else - { - mode = "|UNKNOWN"; - } - - // ARMED STATE DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) - { - mode.prepend("A"); - } - else - { - mode.prepend("D"); - } - - // HARDWARE IN THE LOOP DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL) - { - mode.prepend("HIL:"); - } - - return mode; -} - -const QString& UAS::getShortMode() const -{ - return shortModeText; -} - -/** -* Add the link and connect a signal to it which will be set off when it is destroyed. -*/ -void UAS::addLink(LinkInterface* link) -{ - if (!links->contains(link)) - { - links->append(link); - connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*))); - } -} - -void UAS::removeLink(QObject* object) -{ - LinkInterface* link = dynamic_cast(object); - if (link) - { - links->removeAt(links->indexOf(link)); - } -} - -/** -* @return the list of links -*/ -QList* UAS::getLinks() -{ - return links; -} - -/** -* @rerturn the map of the components -*/ -QMap UAS::getComponents() -{ - return components; -} - -/** -* Set the battery type and the number of cells. -* @param type of the battery -* @param cells Number of cells. -*/ -void UAS::setBattery(BatteryType type, int cells) -{ - this->batteryType = type; - this->cells = cells; - switch (batteryType) - { - case NICD: - break; - case NIMH: - break; - case LIION: - break; - case LIPOLY: - fullVoltage = this->cells * UAS::lipoFull; - emptyVoltage = this->cells * UAS::lipoEmpty; - break; - case LIFE: - break; - case AGZN: - break; - } -} - -/** -* Set the battery specificaitons: empty voltage, warning voltage, and full voltage. -* @param specifications of the battery -*/ -void UAS::setBatterySpecs(const QString& specs) -{ - if (specs.length() == 0 || specs.contains("%")) - { - batteryRemainingEstimateEnabled = false; - bool ok; - QString percent = specs; - percent = percent.remove("%"); - float temp = percent.toFloat(&ok); - if (ok) - { - warnLevelPercent = temp; - } - else - { - emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong"); - } - } - else - { - batteryRemainingEstimateEnabled = true; - QString stringList = specs; - stringList = stringList.remove("V"); - stringList = stringList.remove("v"); - QStringList parts = stringList.split(","); - if (parts.length() == 3) - { - float temp; - bool ok; - // Get the empty voltage - temp = parts.at(0).toFloat(&ok); - if (ok) emptyVoltage = temp; - // Get the warning voltage - temp = parts.at(1).toFloat(&ok); - if (ok) warnVoltage = temp; - // Get the full voltage - temp = parts.at(2).toFloat(&ok); - if (ok) fullVoltage = temp; - } - else - { - emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong"); - } - } -} - -/** -* @return the battery specifications(empty voltage, warning voltage, full voltage) -*/ -QString UAS::getBatterySpecs() -{ - if (batteryRemainingEstimateEnabled) - { - return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage); - } - else - { - return QString("%1%").arg(warnLevelPercent); - } -} - -/** -* @return the time remaining. -*/ -int UAS::calculateTimeRemaining() -{ - quint64 dt = QGC::groundTimeMilliseconds() - startTime; - double seconds = dt / 1000.0f; - double voltDifference = startVoltage - currentVoltage; - if (voltDifference <= 0) voltDifference = 0.00000000001f; - double dischargePerSecond = voltDifference / seconds; - int remaining = static_cast((currentVoltage - emptyVoltage) / dischargePerSecond); - // Can never be below 0 - if (remaining < 0) remaining = 0; - return remaining; -} - -/** - * @return charge level in percent - 0 - 100 - */ -float UAS::getChargeLevel() -{ - if (batteryRemainingEstimateEnabled) - { - if (lpVoltage < emptyVoltage) - { - chargeLevel = 0.0f; - } - else if (lpVoltage > fullVoltage) - { - chargeLevel = 100.0f; - } - else - { - chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage)); - } - } - return chargeLevel; -} - -void UAS::startLowBattAlarm() -{ - if (!lowBattAlarm) - { - GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName())); - QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency())); - lowBattAlarm = true; - } -} - -void UAS::stopLowBattAlarm() -{ - if (lowBattAlarm) - { - GAudioOutput::instance()->stopEmergency(); - lowBattAlarm = false; - } -} +/*=================================================================== +======================================================================*/ + +/** + * @file + * @brief Represents one unmanned aerial vehicle + * + * @author Lorenz Meier + * + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include "UAS.h" +#include "LinkInterface.h" +#include "UASManager.h" +#include "QGC.h" +#include "GAudioOutput.h" +#include "MAVLinkProtocol.h" +#include "QGCMAVLink.h" +#include "LinkManager.h" +#include "SerialLink.h" + +#ifdef QGC_PROTOBUF_ENABLED +#include +#endif + +/** +* Gets the settings from the previous UAS (name, airframe, autopilot, battery specs) +* by calling readSettings. This means the new UAS will have the same settings +* as the previous one created unless one calls deleteSettings in the code after +* creating the UAS. +*/ +UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), + uasId(id), + startTime(QGC::groundTimeMilliseconds()), + commStatus(COMM_DISCONNECTED), + name(""), + autopilot(-1), + links(new QList()), + unknownPackets(), + mavlink(protocol), + waypointManager(this), + thrustSum(0), + thrustMax(10), + startVoltage(-1.0f), + tickVoltage(10.5f), + lastTickVoltageValue(13.0f), + tickLowpassVoltage(12.0f), + warnVoltage(9.5f), + warnLevelPercent(20.0f), + currentVoltage(12.6f), + lpVoltage(12.0f), + batteryRemainingEstimateEnabled(true), + mode(-1), + status(-1), + navMode(-1), + onboardTimeOffset(0), + controlRollManual(true), + controlPitchManual(true), + controlYawManual(true), + controlThrustManual(true), + manualRollAngle(0), + manualPitchAngle(0), + manualYawAngle(0), + manualThrust(0), + receiveDropRate(0), + sendDropRate(0), + lowBattAlarm(false), + positionLock(false), + localX(0.0), + localY(0.0), + localZ(0.0), + latitude(0.0), + longitude(0.0), + altitude(0.0), + roll(0.0), + pitch(0.0), + yaw(0.0), + statusTimeout(new QTimer(this)), + #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) + receivedOverlayTimestamp(0.0), + receivedObstacleListTimestamp(0.0), + receivedPathTimestamp(0.0), + receivedPointCloudTimestamp(0.0), + receivedRGBDImageTimestamp(0.0), + #endif + paramsOnceRequested(false), + airframe(QGC_AIRFRAME_GENERIC), + attitudeKnown(false), + paramManager(NULL), + attitudeStamped(false), + lastAttitude(0), + simulation(0), + isLocalPositionKnown(false), + isGlobalPositionKnown(false), + systemIsArmed(false), + nedPosGlobalOffset(0,0,0), + nedAttGlobalOffset(0,0,0), + connectionLost(false), + lastVoltageWarning(0), + lastNonNullTime(0), + onboardTimeOffsetInvalidCount(0), + hilEnabled(false) + +{ + for (unsigned int i = 0; i<255;++i) + { + componentID[i] = -1; + componentMulti[i] = false; + } + + color = UASInterface::getNextColor(); + setBatterySpecs(QString("9V,9.5V,12.6V")); + connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); + connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings())); + statusTimeout->start(500); + readSettings(); + type = MAV_TYPE_GENERIC; + // Initial signals + emit disarmed(); + emit armingChanged(false); +} + +/** +* Saves the settings of name, airframe, autopilot type and battery specifications +* by calling writeSettings. +*/ +UAS::~UAS() +{ + writeSettings(); + delete links; + delete statusTimeout; + delete simulation; +} + +/** +* Saves the settings of name, airframe, autopilot type and battery specifications +* for the next instantiation of UAS. +*/ +void UAS::writeSettings() +{ + QSettings settings; + settings.beginGroup(QString("MAV%1").arg(uasId)); + settings.setValue("NAME", this->name); + settings.setValue("AIRFRAME", this->airframe); + settings.setValue("AP_TYPE", this->autopilot); + settings.setValue("BATTERY_SPECS", getBatterySpecs()); + settings.endGroup(); + settings.sync(); +} + +/** +* Reads in the settings: name, airframe, autopilot type, and battery specifications +* for the new UAS. +*/ +void UAS::readSettings() +{ + QSettings settings; + settings.beginGroup(QString("MAV%1").arg(uasId)); + this->name = settings.value("NAME", this->name).toString(); + this->airframe = settings.value("AIRFRAME", this->airframe).toInt(); + this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt(); + if (settings.contains("BATTERY_SPECS")) + { + setBatterySpecs(settings.value("BATTERY_SPECS").toString()); + } + settings.endGroup(); +} + +/** +* Deletes the settings origianally read into the UAS by readSettings. +* This is in case one does not want the old values but would rather +* start with the values assigned by the constructor. +*/ +void UAS::deleteSettings() +{ + this->name = ""; + this->airframe = QGC_AIRFRAME_GENERIC; + this->autopilot = -1; + setBatterySpecs(QString("9V,9.5V,12.6V")); +} + +/** +* @ return the id of the uas +*/ +int UAS::getUASID() const +{ + return uasId; +} + +/** +* Update the heartbeat. +*/ +void UAS::updateState() +{ + // Check if heartbeat timed out + quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat; + if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat)) + { + connectionLost = true; + QString audiostring = QString("Link lost to system %1").arg(this->getUASID()); + GAudioOutput::instance()->say(audiostring.toLower()); + } + + // Update connection loss time on each iteration + if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat)) + { + connectionLossTime = heartbeatInterval; + emit heartbeatTimeout(true, heartbeatInterval/1000); + } + + // Connection gained + if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat)) + { + QString audiostring = QString("Link regained to system %1 after %2 seconds").arg(this->getUASID()).arg((int)(connectionLossTime/1000000)); + GAudioOutput::instance()->say(audiostring.toLower()); + connectionLost = false; + connectionLossTime = 0; + emit heartbeatTimeout(false, 0); + } + + // Position lock is set by the MAVLink message handler + // if no position lock is available, indicate an error + if (positionLock) + { + positionLock = false; + } + else + { + if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock) + { + GAudioOutput::instance()->notifyNegative(); + } + } + +//#define MAVLINK_OFFBOARD_CONTROL_MODE_NONE 0 +//#define MAVLINK_OFFBOARD_CONTROL_MODE_RATES 1 +//#define MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE 2 +//#define MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY 3 +//#define MAVLINK_OFFBOARD_CONTROL_MODE_POSITION 4 +//#define MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED 0x10 + +//#warning THIS IS A HUGE HACK AND SHOULD NEVER SHOW UP IN ANY GIT REPOSITORY +// mavlink_message_t message; + +// mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t sp; + +// sp.group = 0; + +// /* set rate mode, set zero rates and 20% throttle */ +// sp.mode = MAVLINK_OFFBOARD_CONTROL_MODE_RATES | MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED; + +// sp.roll[0] = INT16_MAX * 0.0f; +// sp.pitch[0] = INT16_MAX * 0.0f; +// sp.yaw[0] = INT16_MAX * 0.0f; +// sp.thrust[0] = UINT16_MAX * 0.3f; + + +// /* send from system 200 and component 0 */ +// mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(200, 0, &message, &sp); + +// sendMessage(message); +} + +/** +* If the acitve UAS (the UAS that was selected) is not the one that is currently +* active, then change the active UAS to the one that was selected. +*/ +void UAS::setSelected() +{ + if (UASManager::instance()->getActiveUAS() != this) + { + UASManager::instance()->setActiveUAS(this); + emit systemSelected(true); + } +} + +/** +* @return if the active UAS is the current UAS +**/ +bool UAS::getSelected() const +{ + return (UASManager::instance()->getActiveUAS() == this); +} + +void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) +{ + if (!link) return; + if (!links->contains(link)) + { + addLink(link); + // qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName(); + } + + if (!components.contains(message.compid)) + { + QString componentName; + + switch (message.compid) + { + case MAV_COMP_ID_ALL: + { + componentName = "ANONYMOUS"; + break; + } + case MAV_COMP_ID_IMU: + { + componentName = "IMU #1"; + break; + } + case MAV_COMP_ID_CAMERA: + { + componentName = "CAMERA"; + break; + } + case MAV_COMP_ID_MISSIONPLANNER: + { + componentName = "MISSIONPLANNER"; + break; + } + } + + components.insert(message.compid, componentName); + emit componentCreated(uasId, message.compid, componentName); + } + + // qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq; + + // Only accept messages from this system (condition 1) + // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled + // and we already got one attitude packet + if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE)) + { + QString uasState; + QString stateDescription; + + bool multiComponentSourceDetected = false; + bool wrongComponent = false; + + switch (message.compid) + { + case MAV_COMP_ID_IMU_2: + // Prefer IMU 2 over IMU 1 (FIXME) + componentID[message.msgid] = MAV_COMP_ID_IMU_2; + break; + default: + // Do nothing + break; + } + + // Store component ID + if (componentID[message.msgid] == -1) + { + // Prefer the first component + componentID[message.msgid] = message.compid; + } + else + { + // Got this message already + if (componentID[message.msgid] != message.compid) + { + componentMulti[message.msgid] = true; + wrongComponent = true; + } + } + + if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true; + + + switch (message.msgid) + { + case MAVLINK_MSG_ID_HEARTBEAT: + { + if (multiComponentSourceDetected && wrongComponent) + { + break; + } + lastHeartbeat = QGC::groundTimeUsecs(); + emit heartbeat(this); + mavlink_heartbeat_t state; + mavlink_msg_heartbeat_decode(&message, &state); + + // Send the base_mode and system_status values to the plotter. This uses the ground time + // so the Ground Time checkbox must be ticked for these values to display + quint64 time = getUnixTime(); + QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid); + emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time); + emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time); + emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time); + + // Set new type if it has changed + if (this->type != state.type) + { + this->type = state.type; + if (airframe == 0) + { + switch (type) + { + case MAV_TYPE_FIXED_WING: + setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR); + break; + case MAV_TYPE_QUADROTOR: + setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH); + break; + case MAV_TYPE_HEXAROTOR: + setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER); + break; + default: + // Do nothing + break; + } + } + this->autopilot = state.autopilot; + emit systemTypeSet(this, type); + } + + bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY; + + if (systemIsArmed != currentlyArmed) + { + systemIsArmed = currentlyArmed; + emit armingChanged(systemIsArmed); + if (systemIsArmed) + { + emit armed(); + } + else + { + emit disarmed(); + } + } + + QString audiostring = QString("System %1").arg(uasId); + QString stateAudio = ""; + QString modeAudio = ""; + QString navModeAudio = ""; + bool statechanged = false; + bool modechanged = false; + + QString audiomodeText = getAudioModeTextFor(static_cast(state.base_mode)); + + + if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT) + { + statechanged = true; + this->status = state.system_status; + getStatusForCode((int)state.system_status, uasState, stateDescription); + emit statusChanged(this, uasState, stateDescription); + emit statusChanged(this->status); + + shortStateText = uasState; + + // Adjust for better audio + if (uasState == QString("STANDBY")) uasState = QString("standing by"); + if (uasState == QString("EMERGENCY")) uasState = QString("emergency condition"); + if (uasState == QString("CRITICAL")) uasState = QString("critical condition"); + if (uasState == QString("SHUTDOWN")) uasState = QString("shutting down"); + + stateAudio = uasState; + } + + if (this->mode != static_cast(state.base_mode)) + { + modechanged = true; + this->mode = static_cast(state.base_mode); + shortModeText = getShortModeTextFor(this->mode); + + emit modeChanged(this->getUASID(), shortModeText, ""); + + modeAudio = " is now in " + audiomodeText; + } + + if (navMode != state.custom_mode) + { + emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode)); + navMode = state.custom_mode; + //navModeAudio = tr(" changed nav mode to ") + tr("FIXME"); + } + + // AUDIO + if (modechanged && statechanged) + { + // Output both messages + audiostring += modeAudio + " and " + stateAudio; + } + else if (modechanged || statechanged) + { + // Output the one message + audiostring += modeAudio + stateAudio + navModeAudio; + } + + if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)) + { + GAudioOutput::instance()->say(QString("emergency for system %1").arg(this->getUASID())); + QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency())); + } + else if (modechanged || statechanged) + { + GAudioOutput::instance()->stopEmergency(); + GAudioOutput::instance()->say(audiostring.toLower()); + } + } + + break; + case MAVLINK_MSG_ID_SYS_STATUS: + { + if (multiComponentSourceDetected && wrongComponent) + { + break; + } + mavlink_sys_status_t state; + mavlink_msg_sys_status_decode(&message, &state); + + // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present. + quint64 time = getUnixTime(); + QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid); + emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time); + emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time); + emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time); + emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time); + emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time); + emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time); + emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time); + + // Process CPU load. + emit loadChanged(this,state.load/10.0f); + emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time); + + // Battery charge/time remaining/voltage calculations + currentVoltage = state.voltage_battery/1000.0f; + lpVoltage = filterVoltage(currentVoltage); + tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage; + + + // We don't want to tick above the threshold + if (tickLowpassVoltage > tickVoltage) + { + lastTickVoltageValue = tickLowpassVoltage; + } + + if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f) + /* warn if lower than treshold */ + && (lpVoltage < tickVoltage) + /* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */ + && (currentVoltage > 3.3f) + /* warn only if current voltage is really still lower by a reasonable amount */ + && ((currentVoltage - 0.2f) < tickVoltage) + /* warn only every 12 seconds */ + && (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000) + { + GAudioOutput::instance()->say(QString("voltage warning: %1 volts").arg(lpVoltage, 0, 'f', 1, QChar(' '))); + lastVoltageWarning = QGC::groundTimeUsecs(); + lastTickVoltageValue = tickLowpassVoltage; + } + + if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage; + timeRemaining = calculateTimeRemaining(); + if (!batteryRemainingEstimateEnabled && chargeLevel != -1) + { + chargeLevel = state.battery_remaining; + } + emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining); + emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time); + emit voltageChanged(message.sysid, currentVoltage); + emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time); + + // And if the battery current draw is measured, log that also. + if (state.current_battery != -1) + { + emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time); + } + + // LOW BATTERY ALARM + if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3)) + { + startLowBattAlarm(); + } + else + { + stopLowBattAlarm(); + } + + // control_sensors_enabled: + // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control + emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11)); + emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12)); + emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13)); + emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14)); + + // Trigger drop rate updates as needed. Here we convert the incoming + // drop_rate_comm value from 1/100 of a percent in a uint16 to a true + // percentage as a float. We also cap the incoming value at 100% as defined + // by the MAVLink specifications. + if (state.drop_rate_comm > 10000) + { + state.drop_rate_comm = 10000; + } + emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f); + emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time); + } + break; + case MAVLINK_MSG_ID_ATTITUDE: + { + mavlink_attitude_t attitude; + mavlink_msg_attitude_decode(&message, &attitude); + quint64 time = getUnixReferenceTime(attitude.time_boot_ms); + + emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time); + + if (!wrongComponent) + { + lastAttitude = time; + roll = QGC::limitAngleToPMPIf(attitude.roll); + pitch = QGC::limitAngleToPMPIf(attitude.pitch); + yaw = QGC::limitAngleToPMPIf(attitude.yaw); + + // // Emit in angles + + // // Convert yaw angle to compass value + // // in 0 - 360 deg range + // float compass = (yaw/M_PI)*180.0+360.0f; + // if (compass > -10000 && compass < 10000) + // { + // while (compass > 360.0f) { + // compass -= 360.0f; + // } + // } + // else + // { + // // Set to 0, since it is an invalid value + // compass = 0.0f; + // } + + attitudeKnown = true; + emit attitudeChanged(this, roll, pitch, yaw, time); + emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); + } + } + break; + case MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET: + { + mavlink_local_position_ned_system_global_offset_t offset; + mavlink_msg_local_position_ned_system_global_offset_decode(&message, &offset); + nedPosGlobalOffset.setX(offset.x); + nedPosGlobalOffset.setY(offset.y); + nedPosGlobalOffset.setZ(offset.z); + nedAttGlobalOffset.setX(offset.roll); + nedAttGlobalOffset.setY(offset.pitch); + nedAttGlobalOffset.setZ(offset.yaw); + } + break; + case MAVLINK_MSG_ID_HIL_CONTROLS: + { + mavlink_hil_controls_t hil; + mavlink_msg_hil_controls_decode(&message, &hil); + emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode); + } + break; + case MAVLINK_MSG_ID_VFR_HUD: + { + mavlink_vfr_hud_t hud; + mavlink_msg_vfr_hud_decode(&message, &hud); + quint64 time = getUnixTime(); + // Display updated values + emit thrustChanged(this, hud.throttle/100.0); + + if (!attitudeKnown) + { + yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI); + emit attitudeChanged(this, roll, pitch, yaw, time); + } + + emit altitudeChanged(uasId, hud.alt); + emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time); + } + break; + case MAVLINK_MSG_ID_LOCAL_POSITION_NED: + //std::cerr << std::endl; + //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; + { + mavlink_local_position_ned_t pos; + mavlink_msg_local_position_ned_decode(&message, &pos); + quint64 time = getUnixTime(pos.time_boot_ms); + + // Emit position always with component ID + emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); + + + if (!wrongComponent) + { + localX = pos.x; + localY = pos.y; + localZ = pos.z; + + // Emit + + emit localPositionChanged(this, pos.x, pos.y, pos.z, time); + emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); + + // Set internal state + if (!positionLock) { + // If position was not locked before, notify positive + GAudioOutput::instance()->notifyPositive(); + } + positionLock = true; + isLocalPositionKnown = true; + } + } + break; + case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE: + { + mavlink_global_vision_position_estimate_t pos; + mavlink_msg_global_vision_position_estimate_decode(&message, &pos); + quint64 time = getUnixTime(pos.usec); + emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time); + emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time); + } + break; + case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: + //std::cerr << std::endl; + //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; + { + mavlink_global_position_int_t pos; + mavlink_msg_global_position_int_decode(&message, &pos); + quint64 time = getUnixTime(); + latitude = pos.lat/(double)1E7; + longitude = pos.lon/(double)1E7; + altitude = pos.alt/1000.0; + speedX = pos.vx/100.0; + speedY = pos.vy/100.0; + speedZ = pos.vz/100.0; + emit globalPositionChanged(this, latitude, longitude, altitude, time); + emit speedChanged(this, speedX, speedY, speedZ, time); + + // Set internal state + if (!positionLock) + { + // If position was not locked before, notify positive + GAudioOutput::instance()->notifyPositive(); + } + positionLock = true; + isGlobalPositionKnown = true; + //TODO fix this hack for forwarding of global position for patch antenna tracking + forwardMessage(message); + } + break; + case MAVLINK_MSG_ID_GPS_RAW_INT: + { + mavlink_gps_raw_int_t pos; + mavlink_msg_gps_raw_int_decode(&message, &pos); + + // SANITY CHECK + // only accept values in a realistic range + // quint64 time = getUnixTime(pos.time_usec); + quint64 time = getUnixTime(pos.time_usec); + + emit gpsLocalizationChanged(this, pos.fix_type); + // TODO: track localization state not only for gps but also for other loc. sources + int loc_type = pos.fix_type; + if (loc_type == 1) + { + loc_type = 0; + } + emit localizationChanged(this, loc_type); + + if (pos.fix_type > 2) + { + emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time); + latitude = pos.lat/(double)1E7; + longitude = pos.lon/(double)1E7; + altitude = pos.alt/1000.0; + positionLock = true; + isGlobalPositionKnown = true; + + // Check for NaN + int alt = pos.alt; + if (!isnan(alt) && !isinf(alt)) + { + alt = 0; + //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE"); + } + // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time); + // Smaller than threshold and not NaN + + float vel = pos.vel/100.0f; + + if (vel < 1000000 && !isnan(vel) && !isinf(vel)) + { + // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time); + //qDebug() << "GOT GPS RAW"; + // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); + } + else + { + emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel)); + } + } + } + break; + case MAVLINK_MSG_ID_GPS_STATUS: + { + mavlink_gps_status_t pos; + mavlink_msg_gps_status_decode(&message, &pos); + for(int i = 0; i < (int)pos.satellites_visible; i++) + { + emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast(pos.satellite_used[i])); + } + } + break; + case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: + { + mavlink_gps_global_origin_t pos; + mavlink_msg_gps_global_origin_decode(&message, &pos); + emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0); + } + break; + case MAVLINK_MSG_ID_RC_CHANNELS_RAW: + { + mavlink_rc_channels_raw_t channels; + mavlink_msg_rc_channels_raw_decode(&message, &channels); + emit remoteControlRSSIChanged(channels.rssi/255.0f); + emit remoteControlChannelRawChanged(0, channels.chan1_raw); + emit remoteControlChannelRawChanged(1, channels.chan2_raw); + emit remoteControlChannelRawChanged(2, channels.chan3_raw); + emit remoteControlChannelRawChanged(3, channels.chan4_raw); + emit remoteControlChannelRawChanged(4, channels.chan5_raw); + emit remoteControlChannelRawChanged(5, channels.chan6_raw); + emit remoteControlChannelRawChanged(6, channels.chan7_raw); + emit remoteControlChannelRawChanged(7, channels.chan8_raw); + } + break; + case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: + { + mavlink_rc_channels_scaled_t channels; + mavlink_msg_rc_channels_scaled_decode(&message, &channels); + emit remoteControlRSSIChanged(channels.rssi/255.0f); + emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f); + emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f); + emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f); + emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f); + emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f); + emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f); + emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f); + emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f); + } + break; + case MAVLINK_MSG_ID_PARAM_VALUE: + { + mavlink_param_value_t value; + mavlink_msg_param_value_decode(&message, &value); + QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); + // Construct a string stopping at the first NUL (0) character, else copy the whole + // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe) + QString parameterName(bytes); + int component = message.compid; + mavlink_param_union_t val; + val.param_float = value.param_value; + val.type = value.param_type; + + // Insert component if necessary + if (!parameters.contains(component)) + { + parameters.insert(component, new QMap()); + } + + // Insert parameter into registry + if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName); + + // Insert with correct type + switch (value.param_type) + { + case MAV_PARAM_TYPE_REAL32: + { + // Variant + QVariant param(val.param_float); + parameters.value(component)->insert(parameterName, param); + // Emit change + emit parameterChanged(uasId, message.compid, parameterName, param); + emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); +// qDebug() << "RECEIVED PARAM:" << param; + } + break; + case MAV_PARAM_TYPE_UINT32: + { + // Variant + QVariant param(val.param_uint32); + parameters.value(component)->insert(parameterName, param); + // Emit change + emit parameterChanged(uasId, message.compid, parameterName, param); + emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); +// qDebug() << "RECEIVED PARAM:" << param; + } + break; + case MAV_PARAM_TYPE_INT32: + { + // Variant + QVariant param(val.param_int32); + parameters.value(component)->insert(parameterName, param); + // Emit change + emit parameterChanged(uasId, message.compid, parameterName, param); + emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); +// qDebug() << "RECEIVED PARAM:" << param; + } + break; + default: + qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type; + } + } + break; + case MAVLINK_MSG_ID_COMMAND_ACK: + { + mavlink_command_ack_t ack; + mavlink_msg_command_ack_decode(&message, &ack); + switch (ack.result) + { + case MAV_RESULT_ACCEPTED: + { + emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command)); + } + break; + case MAV_RESULT_TEMPORARILY_REJECTED: + { + emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command)); + } + break; + case MAV_RESULT_DENIED: + { + emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command)); + } + break; + case MAV_RESULT_UNSUPPORTED: + { + emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command)); + } + break; + case MAV_RESULT_FAILED: + { + emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command)); + } + break; + } + } + case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT: + { + mavlink_roll_pitch_yaw_thrust_setpoint_t out; + mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out); + quint64 time = getUnixTimeFromMs(out.time_boot_ms); + emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time); + } + break; + case MAVLINK_MSG_ID_MISSION_COUNT: + { + mavlink_mission_count_t wpc; + mavlink_msg_mission_count_decode(&message, &wpc); + if(wpc.target_system == mavlink->getSystemId() || wpc.target_system == 0) + { + waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count); + } + else + { + qDebug() << "Got waypoint message, but was wrong system id" << wpc.target_system; + } + } + break; + + case MAVLINK_MSG_ID_MISSION_ITEM: + { + mavlink_mission_item_t wp; + mavlink_msg_mission_item_decode(&message, &wp); + //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z; + if(wp.target_system == mavlink->getSystemId() || wp.target_system == 0) + { + waypointManager.handleWaypoint(message.sysid, message.compid, &wp); + } + else + { + qDebug() << "Got waypoint message, but was wrong system id" << wp.target_system; + } + } + break; + + case MAVLINK_MSG_ID_MISSION_ACK: + { + mavlink_mission_ack_t wpa; + mavlink_msg_mission_ack_decode(&message, &wpa); + if((wpa.target_system == mavlink->getSystemId() || wpa.target_system == 0) && + (wpa.target_component == mavlink->getComponentId() || wpa.target_component == 0)) + { + waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa); + } + } + break; + + case MAVLINK_MSG_ID_MISSION_REQUEST: + { + mavlink_mission_request_t wpr; + mavlink_msg_mission_request_decode(&message, &wpr); + if(wpr.target_system == mavlink->getSystemId() || wpr.target_system == 0) + { + waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr); + } + else + { + qDebug() << "Got waypoint message, but was wrong system id" << wpr.target_system; + } + } + break; + + case MAVLINK_MSG_ID_MISSION_ITEM_REACHED: + { + mavlink_mission_item_reached_t wpr; + mavlink_msg_mission_item_reached_decode(&message, &wpr); + waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr); + QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq); + GAudioOutput::instance()->say(text); + emit textMessageReceived(message.sysid, message.compid, 0, text); + } + break; + + case MAVLINK_MSG_ID_MISSION_CURRENT: + { + mavlink_mission_current_t wpc; + mavlink_msg_mission_current_decode(&message, &wpc); + waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc); + } + break; + + case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT: + { + if (multiComponentSourceDetected && wrongComponent) + { + break; + } + mavlink_local_position_setpoint_t p; + mavlink_msg_local_position_setpoint_decode(&message, &p); + emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs()); + } + break; + case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT: + { + mavlink_set_local_position_setpoint_t p; + mavlink_msg_set_local_position_setpoint_decode(&message, &p); + emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw); + } + break; + case MAVLINK_MSG_ID_STATUSTEXT: + { + QByteArray b; + b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN); + mavlink_msg_statustext_get_text(&message, b.data()); + //b.append('\0'); + QString text = QString(b); + int severity = mavlink_msg_statustext_get_severity(&message); + //qDebug() << "RECEIVED STATUS:" << text;false + //emit statusTextReceived(severity, text); + + if (text.startsWith("#audio:")) + { + text.remove("#audio:"); + emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text); + GAudioOutput::instance()->say(text, severity); + } + else + { + emit textMessageReceived(uasId, message.compid, severity, text); + } + } + break; + case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW: + { + mavlink_servo_output_raw_t raw; + mavlink_msg_servo_output_raw_decode(&message, &raw); + + if (hilEnabled) + { + emit hilActuatorsChanged(static_cast(getUnixTimeFromMs(raw.time_boot_ms)), static_cast(raw.servo1_raw), + static_cast(raw.servo2_raw), static_cast(raw.servo3_raw), + static_cast(raw.servo4_raw), static_cast(raw.servo5_raw), static_cast(raw.servo6_raw), + static_cast(raw.servo7_raw), static_cast(raw.servo8_raw)); + } + } + break; +#ifdef MAVLINK_ENABLED_PIXHAWK + case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE: + { + mavlink_data_transmission_handshake_t p; + mavlink_msg_data_transmission_handshake_decode(&message, &p); + imageSize = p.size; + imagePackets = p.packets; + imagePayload = p.payload; + imageQuality = p.jpg_quality; + imageType = p.type; + imageWidth = p.width; + imageHeight = p.height; + imageStart = QGC::groundTimeMilliseconds(); + } + break; + + case MAVLINK_MSG_ID_ENCAPSULATED_DATA: + { + mavlink_encapsulated_data_t img; + mavlink_msg_encapsulated_data_decode(&message, &img); + int seq = img.seqnr; + int pos = seq * imagePayload; + + // Check if we have a valid transaction + if (imagePackets == 0) + { + // NO VALID TRANSACTION - ABORT + // Restart statemachine + imagePacketsArrived = 0; + } + + for (int i = 0; i < imagePayload; ++i) + { + if (pos <= imageSize) { + imageRecBuffer[pos] = img.data[i]; + } + ++pos; + } + + ++imagePacketsArrived; + + // emit signal if all packets arrived + if ((imagePacketsArrived >= imagePackets)) + { + // Restart statemachine + imagePacketsArrived = 0; + emit imageReady(this); + //qDebug() << "imageReady emitted. all packets arrived"; + } + } + break; + + + +#endif + // case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT: + // { + // mavlink_object_detection_event_t event; + // mavlink_msg_object_detection_event_decode(&message, &event); + // QString str(event.name); + // emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance); + // } + // break; + // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET + // case MAVLINK_MSG_ID_MEMORY_VECT: + // { + // mavlink_memory_vect_t vect; + // mavlink_msg_memory_vect_decode(&message, &vect); + // QString str("mem_%1"); + // quint64 time = getUnixTime(0); + // int16_t *mem0 = (int16_t *)&vect.value[0]; + // uint16_t *mem1 = (uint16_t *)&vect.value[0]; + // int32_t *mem2 = (int32_t *)&vect.value[0]; + // // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem + // float *mem4 = (float *)&vect.value[0]; + // if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ; + // if ( vect.ver == 1) + // { + // switch (vect.type) { + // default: + // case 0: + // for (int i = 0; i < 16; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time); + // break; + // case 1: + // for (int i = 0; i < 16; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time); + // break; + // case 2: + // for (int i = 0; i < 16; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time); + // break; + // case 3: + // for (int i = 0; i < 16; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time); + // break; + // case 4: + // for (int i = 0; i < 8; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); + // break; + // case 5: + // for (int i = 0; i < 8; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); + // break; + // case 6: + // for (int i = 0; i < 8; i++) + // // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time); + // break; + // } + // } + // } + // break; +#ifdef MAVLINK_ENABLED_UALBERTA + case MAVLINK_MSG_ID_NAV_FILTER_BIAS: + { + mavlink_nav_filter_bias_t bias; + mavlink_msg_nav_filter_bias_decode(&message, &bias); + quint64 time = getUnixTime(); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time); + } + break; + case MAVLINK_MSG_ID_RADIO_CALIBRATION: + { + mavlink_radio_calibration_t radioMsg; + mavlink_msg_radio_calibration_decode(&message, &radioMsg); + QVector aileron; + QVector elevator; + QVector rudder; + QVector gyro; + QVector pitch; + QVector throttle; + + for (int i=0; i radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle); + emit radioCalibrationReceived(radioData); + delete radioData; + } + break; + +#endif + // Messages to ignore + case MAVLINK_MSG_ID_RAW_IMU: + case MAVLINK_MSG_ID_SCALED_IMU: + case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: + case MAVLINK_MSG_ID_RAW_PRESSURE: + case MAVLINK_MSG_ID_SCALED_PRESSURE: + case MAVLINK_MSG_ID_OPTICAL_FLOW: + case MAVLINK_MSG_ID_DEBUG_VECT: + case MAVLINK_MSG_ID_DEBUG: + case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: + case MAVLINK_MSG_ID_NAMED_VALUE_INT: + case MAVLINK_MSG_ID_MANUAL_CONTROL: + case MAVLINK_MSG_ID_HIGHRES_IMU: + break; + default: + { + if (!unknownPackets.contains(message.msgid)) + { + unknownPackets.append(message.msgid); + QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid); + //GAudioOutput::instance()->say(errString+tr(", please check console for details.")); + emit textMessageReceived(uasId, message.compid, 255, errString); + std::cout << "Unable to decode message from system " << std::dec << static_cast(message.sysid) << " with message id:" << static_cast(message.msgid) << std::endl; + //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast(message.acid) << " with message id:" << static_cast(message.msgid) << std::endl; + } + } + break; + } + } +} + + +#if defined(QGC_PROTOBUF_ENABLED) +/** +* Receive an extended message. +* @param link +* @param message +*/ +void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr message) +{ + if (!link) + { + return; + } + if (!links->contains(link)) + { + addLink(link); + } + + const google::protobuf::Descriptor* descriptor = message->GetDescriptor(); + if (!descriptor) + { + return; + } + + const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header"); + if (!headerField) + { + return; + } + + const google::protobuf::Descriptor* headerDescriptor = headerField->message_type(); + if (!headerDescriptor) + { + return; + } + + const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid"); + if (!sourceSysIdField) + { + return; + } + + const google::protobuf::Reflection* reflection = message->GetReflection(); + const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField); + const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection(); + + int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField); + + if (source_sysid != uasId) + { + return; + } + +#ifdef QGC_USE_PIXHAWK_MESSAGES + if (message->GetTypeName() == overlay.GetTypeName()) + { + receivedOverlayTimestamp = QGC::groundTimeSeconds(); + overlayMutex.lock(); + overlay.CopyFrom(*message); + overlayMutex.unlock(); + emit overlayChanged(this); + } + else if (message->GetTypeName() == obstacleList.GetTypeName()) + { + receivedObstacleListTimestamp = QGC::groundTimeSeconds(); + obstacleListMutex.lock(); + obstacleList.CopyFrom(*message); + obstacleListMutex.unlock(); + emit obstacleListChanged(this); + } + else if (message->GetTypeName() == path.GetTypeName()) + { + receivedPathTimestamp = QGC::groundTimeSeconds(); + pathMutex.lock(); + path.CopyFrom(*message); + pathMutex.unlock(); + emit pathChanged(this); + } + else if (message->GetTypeName() == pointCloud.GetTypeName()) + { + receivedPointCloudTimestamp = QGC::groundTimeSeconds(); + pointCloudMutex.lock(); + pointCloud.CopyFrom(*message); + pointCloudMutex.unlock(); + emit pointCloudChanged(this); + } + else if (message->GetTypeName() == rgbdImage.GetTypeName()) + { + receivedRGBDImageTimestamp = QGC::groundTimeSeconds(); + rgbdImageMutex.lock(); + rgbdImage.CopyFrom(*message); + rgbdImageMutex.unlock(); + emit rgbdImageChanged(this); + } +#endif +} + +#endif + +/** +* Set the home position of the UAS. +* @param lat The latitude fo the home position +* @param lon The longitute of the home position +* @param alt The altitude of the home position +*/ +void UAS::setHomePosition(double lat, double lon, double alt) +{ + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Warning); + msgBox.setText("Setting new World Coordinate Frame Origin"); + msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location"); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); + msgBox.setDefaultButton(QMessageBox::Cancel); + int ret = msgBox.exec(); + + // Close the message box shortly after the click to prevent accidental clicks + QTimer::singleShot(5000, &msgBox, SLOT(reject())); + + + if (ret == QMessageBox::Yes) + { + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt); + // Send message twice to increase chance that it reaches its goal + sendMessage(msg); + + // Send new home position to UAS + mavlink_set_gps_global_origin_t home; + home.target_system = uasId; + home.latitude = lat*1E7; + home.longitude = lon*1E7; + home.altitude = alt*1000; + qDebug() << "lat:" << home.latitude << " lon:" << home.longitude; + mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home); + sendMessage(msg); + } +} + +/** +* Set the origin to the current GPS location. +**/ +void UAS::setLocalOriginAtCurrentGPSPosition() +{ + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Warning); + msgBox.setText("Setting new World Coordinate Frame Origin"); + msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location"); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); + msgBox.setDefaultButton(QMessageBox::Cancel); + int ret = msgBox.exec(); + + // Close the message box shortly after the click to prevent accidental clicks + QTimer::singleShot(5000, &msgBox, SLOT(reject())); + + + if (ret == QMessageBox::Yes) + { + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0); + // Send message twice to increase chance that it reaches its goal + sendMessage(msg); + } +} + +/** +* Set a local position setpoint. +* @param x postion +* @param y position +* @param z position +*/ +void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) +{ +#ifdef MAVLINK_ENABLED_PIXHAWK + mavlink_message_t msg; + mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0); + sendMessage(msg); +#else + Q_UNUSED(x); + Q_UNUSED(y); + Q_UNUSED(z); + Q_UNUSED(yaw); +#endif +} + +/** +* Set a offset of the local position. +* @param x position +* @param y position +* @param z position +* @param yaw +*/ +void UAS::setLocalPositionOffset(float x, float y, float z, float yaw) +{ +#ifdef MAVLINK_ENABLED_PIXHAWK + mavlink_message_t msg; + mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw); + sendMessage(msg); +#else + Q_UNUSED(x); + Q_UNUSED(y); + Q_UNUSED(z); + Q_UNUSED(yaw); +#endif +} + +void UAS::startRadioControlCalibration() +{ + mavlink_message_t msg; + // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0); + sendMessage(msg); +} + +void UAS::startDataRecording() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0); + sendMessage(msg); +} + +void UAS::stopDataRecording() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0); + sendMessage(msg); +} + +void UAS::startMagnetometerCalibration() +{ + mavlink_message_t msg; + // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0); + sendMessage(msg); +} + +void UAS::startGyroscopeCalibration() +{ + mavlink_message_t msg; + // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0); + sendMessage(msg); +} + +void UAS::startPressureCalibration() +{ + mavlink_message_t msg; + // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0); + sendMessage(msg); +} + +/** +* Check if time is smaller than 40 years, assuming no system without Unix +* timestamp runs longer than 40 years continuously without reboot. In worst case +* this will add/subtract the communication delay between GCS and MAV, it will +* never alter the timestamp in a safety critical way. +*/ +quint64 UAS::getUnixReferenceTime(quint64 time) +{ + // Same as getUnixTime, but does not react to attitudeStamped mode + if (time == 0) + { + // qDebug() << "XNEW time:" < has to be + // a Unix epoch timestamp. Do nothing. + return time/1000; + } +} + +/** +* @warning If attitudeStamped is enabled, this function will not actually return +* the precise time stamp of this measurement augmented to UNIX time, but will +* MOVE the timestamp IN TIME to match the last measured attitude. There is no +* reason why one would want this, except for system setups where the onboard +* clock is not present or broken and datasets should be collected that are still +* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE +* SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL! +*/ +quint64 UAS::getUnixTimeFromMs(quint64 time) +{ + return getUnixTime(time*1000); +} + +/** +* @warning If attitudeStamped is enabled, this function will not actually return +* the precise time stam of this measurement augmented to UNIX time, but will +* MOVE the timestamp IN TIME to match the last measured attitude. There is no +* reason why one would want this, except for system setups where the onboard +* clock is not present or broken and datasets should be collected that are +* still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED +* RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL! +*/ +quint64 UAS::getUnixTime(quint64 time) +{ + quint64 ret = 0; + if (attitudeStamped) + { + ret = lastAttitude; + } + + if (time == 0) + { + ret = QGC::groundTimeMilliseconds(); + } + // Check if time is smaller than 40 years, + // assuming no system without Unix timestamp + // runs longer than 40 years continuously without + // reboot. In worst case this will add/subtract the + // communication delay between GCS and MAV, + // it will never alter the timestamp in a safety + // critical way. + // + // Calculation: + // 40 years + // 365 days + // 24 hours + // 60 minutes + // 60 seconds + // 1000 milliseconds + // 1000 microseconds +#ifndef _MSC_VER + else if (time < 1261440000000000LLU) +#else + else if (time < 1261440000000000) +#endif + { + // qDebug() << "GEN time:" << time/1000 + onboardTimeOffset; + if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100)) + { + lastNonNullTime = time; + onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000; + } + if (time > lastNonNullTime) lastNonNullTime = time; + + ret = time/1000 + onboardTimeOffset; + } + else + { + // Time is not zero and larger than 40 years -> has to be + // a Unix epoch timestamp. Do nothing. + ret = time/1000; + } + + return ret; +} + +/** +* @param component that will be searched for in the map of parameters. +*/ +QList UAS::getParameterNames(int component) +{ + if (parameters.contains(component)) + { + return parameters.value(component)->keys(); + } + else + { + return QList(); + } +} + +QList UAS::getComponentIds() +{ + return parameters.keys(); +} + +/** +* @param mode that UAS is to be set to. +*/ +void UAS::setMode(int mode) +{ + //this->mode = mode; //no call assignament, update receive message from UAS + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode, (uint16_t)navMode); + sendMessage(msg); + qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode; +} + +/** +* Send a message to every link that is connected. +* @param message that is to be sent +*/ +void UAS::sendMessage(mavlink_message_t message) +{ + if (!LinkManager::instance()) return; + // Emit message on all links that are currently connected + foreach (LinkInterface* link, *links) + { + if (LinkManager::instance()->getLinks().contains(link)) + { + sendMessage(link, message); + } + else + { + // Remove from list + links->removeAt(links->indexOf(link)); + } + } +} + +/** +* Forward a message to all links that are currently connected. +* @param message that is to be forwarded +*/ +void UAS::forwardMessage(mavlink_message_t message) +{ + // Emit message on all links that are currently connected + QListlink_list = LinkManager::instance()->getLinksForProtocol(mavlink); + + foreach(LinkInterface* link, link_list) + { + if (link) + { + SerialLink* serial = dynamic_cast(link); + if(serial != 0) + { + for(int i=0; isize(); i++) + { + if(serial != links->at(i)) + { + qDebug()<<"Antenna tracking: Forwarding Over link: "<getName()<<" "<getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]); + // If link is connected + if (link->isConnected()) + { + // Send the portion of the buffer now occupied by the message + link->writeBytes((const char*)buffer, len); + } +} + +/** + * @param value battery voltage + */ +float UAS::filterVoltage(float value) const +{ + return lpVoltage * 0.7f + value * 0.3f; +} + +/** +* The mode can be preflight or unknown. +* @Return the mode of the autopilot +*/ +QString UAS::getNavModeText(int mode) +{ + if (autopilot == MAV_AUTOPILOT_PIXHAWK) + { + switch (mode) + { + case 0: + return QString("PREFLIGHT"); + break; + default: + return QString("UNKNOWN"); + } + } + else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) + { + return QString("UNKNOWN"); + } + else if (autopilot == MAV_AUTOPILOT_OPENPILOT) + { + return QString("UNKNOWN"); + } + // If nothing matches, return unknown + return QString("UNKNOWN"); +} + +/** +* Get the status of the code and a description of the status. +* Status can be unitialized, booting up, calibrating sensors, active +* standby, cirtical, emergency, shutdown or unknown. +*/ +void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription) +{ + switch (statusCode) + { + case MAV_STATE_UNINIT: + uasState = tr("UNINIT"); + stateDescription = tr("Unitialized, booting up."); + break; + case MAV_STATE_BOOT: + uasState = tr("BOOT"); + stateDescription = tr("Booting system, please wait."); + break; + case MAV_STATE_CALIBRATING: + uasState = tr("CALIBRATING"); + stateDescription = tr("Calibrating sensors, please wait."); + break; + case MAV_STATE_ACTIVE: + uasState = tr("ACTIVE"); + stateDescription = tr("Active, normal operation."); + break; + case MAV_STATE_STANDBY: + uasState = tr("STANDBY"); + stateDescription = tr("Standby mode, ready for launch."); + break; + case MAV_STATE_CRITICAL: + uasState = tr("CRITICAL"); + stateDescription = tr("FAILURE: Continuing operation."); + break; + case MAV_STATE_EMERGENCY: + uasState = tr("EMERGENCY"); + stateDescription = tr("EMERGENCY: Land Immediately!"); + break; + //case MAV_STATE_HILSIM: + //uasState = tr("HIL SIM"); + //stateDescription = tr("HIL Simulation, Sensors read from SIM"); + //break; + + case MAV_STATE_POWEROFF: + uasState = tr("SHUTDOWN"); + stateDescription = tr("Powering off system."); + break; + + default: + uasState = tr("UNKNOWN"); + stateDescription = tr("Unknown system state"); + break; + } +} + +QImage UAS::getImage() +{ +#ifdef MAVLINK_ENABLED_PIXHAWK + +// qDebug() << "IMAGE TYPE:" << imageType; + + // RAW greyscale + if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U) + { + // TODO FIXME + int imgColors = 255;//imageSize/(imageWidth*imageHeight); + //const int headerSize = 15; + + // Construct PGM header + QString header("P5\n%1 %2\n%3\n"); + header = header.arg(imageWidth).arg(imageHeight).arg(imgColors); + + QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size()); + tmpImage.append(imageRecBuffer); + + //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header; + + if (imageRecBuffer.isNull()) + { + qDebug()<< "could not convertToPGM()"; + return QImage(); + } + + if (!image.loadFromData(tmpImage, "PGM")) + { + qDebug()<< "could not create extracted image"; + return QImage(); + } + + } + // BMP with header + else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP || + imageType == MAVLINK_DATA_STREAM_IMG_JPEG || + imageType == MAVLINK_DATA_STREAM_IMG_PGM || + imageType == MAVLINK_DATA_STREAM_IMG_PNG) + { + if (!image.loadFromData(imageRecBuffer)) + { + qDebug() << "Loading data from image buffer failed!"; + } + } + // Restart statemachine + imagePacketsArrived = 0; + //imageRecBuffer.clear(); + return image; +#else + return QImage(); +#endif + +} + +void UAS::requestImage() +{ +#ifdef MAVLINK_ENABLED_PIXHAWK + qDebug() << "trying to get an image from the uas..."; + + // check if there is already an image transmission going on + if (imagePacketsArrived == 0) + { + mavlink_message_t msg; + mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50); + sendMessage(msg); + } +#endif +} + + +/* MANAGEMENT */ + +/** + * + * @return The uptime in milliseconds + * + */ +quint64 UAS::getUptime() const +{ + if(startTime == 0) + { + return 0; + } + else + { + return QGC::groundTimeMilliseconds() - startTime; + } +} + +int UAS::getCommunicationStatus() const +{ + return commStatus; +} + +void UAS::requestParameters() +{ + mavlink_message_t msg; + mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL); + sendMessage(msg); + qDebug() << __FILE__ << __LINE__ << "LOADING PARAM LIST"; +} + +void UAS::writeParametersToStorage() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); + qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE; + sendMessage(msg); +} + +void UAS::readParametersFromStorage() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0); + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableAllDataTransmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + // 0 is a magic ID and will enable/disable the standard message set except for heartbeat + stream.req_stream_id = MAV_DATA_STREAM_ALL; + // Select the update rate in Hz the message should be send + // All messages will be send with their default rate + // TODO: use 0 to turn off and get rid of enable/disable? will require + // a different magic flag for turning on defaults, possibly something really high like 1111 ? + stream.req_message_rate = 0; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableRawSensorDataTransmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableExtendedSystemStatusTransmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableRCChannelDataTransmission(int rate) +{ +#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES) + mavlink_message_t msg; + mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled); + sendMessage(msg); +#else + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); +#endif +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableRawControllerDataTransmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); +} + +//void UAS::enableRawSensorFusionTransmission(int rate) +//{ +// // Buffers to write data to +// mavlink_message_t msg; +// mavlink_request_data_stream_t stream; +// // Select the message to request from now on +// stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION; +// // Select the update rate in Hz the message should be send +// stream.req_message_rate = rate; +// // Start / stop the message +// stream.start_stop = (rate) ? 1 : 0; +// // The system which should take this command +// stream.target_system = uasId; +// // The component / subsystem which should take this command +// stream.target_component = 0; +// // Encode and send the message +// mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); +// // Send message twice to increase chance of reception +// sendMessage(msg); +// sendMessage(msg); +//} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enablePositionTransmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_POSITION; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableExtra1Transmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_EXTRA1; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableExtra2Transmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_EXTRA2; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); + sendMessage(msg); +} + +/** +* @param rate The update rate in Hz the message should be sent +*/ +void UAS::enableExtra3Transmission(int rate) +{ + // Buffers to write data to + mavlink_message_t msg; + mavlink_request_data_stream_t stream; + // Select the message to request from now on + stream.req_stream_id = MAV_DATA_STREAM_EXTRA3; + // Select the update rate in Hz the message should be send + stream.req_message_rate = rate; + // Start / stop the message + stream.start_stop = (rate) ? 1 : 0; + // The system which should take this command + stream.target_system = uasId; + // The component / subsystem which should take this command + stream.target_component = 0; + // Encode and send the message + mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); + // Send message twice to increase chance of reception + sendMessage(msg); + sendMessage(msg); +} + +/** + * Set a parameter value onboard + * + * @param component The component to set the parameter + * @param id Name of the parameter + */ +void UAS::setParameter(const int component, const QString& id, const QVariant& value) +{ + if (!id.isNull()) + { + mavlink_message_t msg; + mavlink_param_set_t p; + mavlink_param_union_t union_value; + + // Assign correct value based on QVariant + switch (value.type()) + { + case QVariant::Int: + union_value.param_int32 = value.toInt(); + p.param_type = MAV_PARAM_TYPE_INT32; + break; + case QVariant::UInt: + union_value.param_uint32 = value.toUInt(); + p.param_type = MAV_PARAM_TYPE_UINT32; + break; + case QMetaType::Float: + union_value.param_float = value.toFloat(); + p.param_type = MAV_PARAM_TYPE_REAL32; + break; + default: + qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE"; + return; + } + + p.param_value = union_value.param_float; + p.target_system = (uint8_t)uasId; + p.target_component = (uint8_t)component; + + //qDebug() << "SENT PARAM:" << value; + + // Copy string into buffer, ensuring not to exceed the buffer size + for (unsigned int i = 0; i < sizeof(p.param_id); i++) + { + // String characters + if ((int)i < id.length()) + { + p.param_id[i] = id.toAscii()[i]; + } + else + { + // Fill rest with zeros + p.param_id[i] = 0; + } + } + mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p); + sendMessage(msg); + } +} + +/** +* Request parameter, use parameter name to request it. +*/ +void UAS::requestParameter(int component, int id) +{ + // Request parameter, use parameter name to request it + mavlink_message_t msg; + mavlink_param_request_read_t read; + read.param_index = id; + read.param_id[0] = '\0'; // Enforce null termination + read.target_system = uasId; + read.target_component = component; + mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read); + sendMessage(msg); + //qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id; +} + +/** +* Request a parameter, use parameter name to request it. +*/ +void UAS::requestParameter(int component, const QString& parameter) +{ + // Request parameter, use parameter name to request it + mavlink_message_t msg; + mavlink_param_request_read_t read; + read.param_index = -1; + // Copy full param name or maximum max field size + if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN) + { + emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1)); + } + memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)); + read.param_id[15] = '\0'; // Enforce null termination + read.target_system = uasId; + read.target_component = component; + mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read); + sendMessage(msg); + qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter; +} + +/** +* @param systemType Type of MAV. +*/ +void UAS::setSystemType(int systemType) +{ + if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END)) + { + type = systemType; + + // If the airframe is still generic, change it to a close default type + if (airframe == 0) + { + switch (systemType) + { + case MAV_TYPE_FIXED_WING: + airframe = QGC_AIRFRAME_EASYSTAR; + break; + case MAV_TYPE_QUADROTOR: + airframe = QGC_AIRFRAME_MIKROKOPTER; + break; + } + } + emit systemSpecsChanged(uasId); + } +} + +void UAS::setUASName(const QString& name) +{ + if (name != "") + { + this->name = name; + writeSettings(); + emit nameChanged(name); + emit systemSpecsChanged(uasId); + } +} + +void UAS::executeCommand(MAV_CMD command) +{ + mavlink_message_t msg; + mavlink_command_long_t cmd; + cmd.command = (uint16_t)command; + cmd.confirmation = 0; + cmd.param1 = 0.0f; + cmd.param2 = 0.0f; + cmd.param3 = 0.0f; + cmd.param4 = 0.0f; + cmd.param5 = 0.0f; + cmd.param6 = 0.0f; + cmd.param7 = 0.0f; + cmd.target_system = uasId; + cmd.target_component = 0; + mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); + sendMessage(msg); +} + +void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) +{ + mavlink_message_t msg; + mavlink_command_long_t cmd; + cmd.command = (uint16_t)command; + cmd.confirmation = confirmation; + cmd.param1 = param1; + cmd.param2 = param2; + cmd.param3 = param3; + cmd.param4 = param4; + cmd.param5 = param5; + cmd.param6 = param6; + cmd.param7 = param7; + cmd.target_system = uasId; + cmd.target_component = component; + mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); + sendMessage(msg); +} + +/** + * Launches the system + * + */ +void UAS::launch() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0); + sendMessage(msg); +} + +/** + * @warning Depending on the UAS, this might make the rotors of a helicopter spinning + * + */ +void UAS::armSystem() +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_SAFETY_ARMED, navMode); + sendMessage(msg); +} + +/** + * @warning Depending on the UAS, this might completely stop all motors. + * + */ +void UAS::disarmSystem() +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & ~MAV_MODE_FLAG_SAFETY_ARMED, navMode); + sendMessage(msg); +} + +/** +* Set the manual control commands. +* This can only be done if the system has manual inputs enabled and is armed. +*/ +void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons) +{ + // Scale values + double rollPitchScaling = 1.0f * 1000.0f; + double yawScaling = 1.0f * 1000.0f; + double thrustScaling = 1.0f * 1000.0f; + + manualRollAngle = roll * rollPitchScaling; + manualPitchAngle = pitch * rollPitchScaling; + manualYawAngle = yaw * yawScaling; + manualThrust = thrust * thrustScaling; + + // If system has manual inputs enabled and is armed + if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED)) + { + mavlink_message_t message; + mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualPitchAngle, (float)manualRollAngle, (float)manualThrust, (float)manualYawAngle, buttons); + sendMessage(message); + //qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; + + emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds()); + } + else + { + //qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first"; + } +} + +void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw) +{ + // If system has manual inputs enabled and is armed + if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED)) + { + mavlink_message_t message; + mavlink_msg_setpoint_6dof_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)x, (float)y, (float)z, (float)roll, (float)pitch, (float)yaw); + sendMessage(message); + qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGE: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw; + + //emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds()); + } + else + { + qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first"; + } +} + +/** +* @return the type of the system +*/ +int UAS::getSystemType() +{ + return this->type; +} + +/** +* @param buttonIndex +*/ +void UAS::receiveButton(int buttonIndex) +{ + switch (buttonIndex) + { + case 0: + + break; + case 1: + + break; + default: + + break; + } + // qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!"; + +} + +/** +* Halt the uas. +*/ +void UAS::halt() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0); + sendMessage(msg); +} + +/** +* Make the UAS move. +*/ +void UAS::go() +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0); + sendMessage(msg); +} + +/** +* Order the robot to return home +*/ +void UAS::home() +{ + mavlink_message_t msg; + + double latitude = UASManager::instance()->getHomeLatitude(); + double longitude = UASManager::instance()->getHomeLongitude(); + double altitude = UASManager::instance()->getHomeAltitude(); + int frame = UASManager::instance()->getHomeFrame(); + + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude); + sendMessage(msg); +} + +/** +* Order the robot to land on the runway +*/ +void UAS::land() +{ + mavlink_message_t msg; + + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_LAND, 1, 0, 0, 0, 0, 0, 0, 0); + sendMessage(msg); +} + +/** + * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation + * and might differ between systems. + */ +void UAS::emergencySTOP() +{ + // FIXME MAVLINKV10PORTINGNEEDED + halt(); +} + +/** + * Shut down this mav - All onboard systems are immediately shut down (e.g. the + * main power line is cut). + * @warning This might lead to a crash. + * + * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards + */ +bool UAS::emergencyKILL() +{ + halt(); + // FIXME MAVLINKV10PORTINGNEEDED + // bool result = false; + // QMessageBox msgBox; + // msgBox.setIcon(QMessageBox::Critical); + // msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS"); + // msgBox.setInformativeText("Do you want to cut power on all systems?"); + // msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); + // msgBox.setDefaultButton(QMessageBox::Cancel); + // int ret = msgBox.exec(); + + // // Close the message box shortly after the click to prevent accidental clicks + // QTimer::singleShot(5000, &msgBox, SLOT(reject())); + + + // if (ret == QMessageBox::Yes) + // { + // mavlink_message_t msg; + // // TODO Replace MG System ID with static function call and allow to change ID in GUI + // mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_KILL); + // // Send message twice to increase chance of reception + // sendMessage(msg); + // sendMessage(msg); + // result = true; + // } + // return result; + return false; +} + +/** +* If enabled, connect the flight gear link. +*/ +void UAS::enableHilFlightGear(bool enable, QString options) +{ + QGCFlightGearLink* link = dynamic_cast(simulation); + if (!link || !simulation) { + // Delete wrong sim + if (simulation) { + stopHil(); + delete simulation; + } + simulation = new QGCFlightGearLink(this, options); + } + // Connect Flight Gear Link + link = dynamic_cast(simulation); + link->setStartupArguments(options); + if (enable) + { + startHil(); + } + else + { + stopHil(); + } +} + +/** +* If enabled, connect the X-plane gear link. +*/ +void UAS::enableHilXPlane(bool enable) +{ + QGCXPlaneLink* link = dynamic_cast(simulation); + if (!link || !simulation) { + if (simulation) { + stopHil(); + delete simulation; + } + qDebug() << "CREATED NEW XPLANE LINK"; + simulation = new QGCXPlaneLink(this); + } + // Connect X-Plane Link + if (enable) + { + startHil(); + } + else + { + stopHil(); + } +} + +/** +* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot) +* @param roll Roll angle (rad) +* @param pitch Pitch angle (rad) +* @param yaw Yaw angle (rad) +* @param rollspeed Roll angular speed (rad/s) +* @param pitchspeed Pitch angular speed (rad/s) +* @param yawspeed Yaw angular speed (rad/s) +* @param lat Latitude, expressed as * 1E7 +* @param lon Longitude, expressed as * 1E7 +* @param alt Altitude in meters, expressed as * 1000 (millimeters) +* @param vx Ground X Speed (Latitude), expressed as m/s * 100 +* @param vy Ground Y Speed (Longitude), expressed as m/s * 100 +* @param vz Ground Z Speed (Altitude), expressed as m/s * 100 +* @param xacc X acceleration (mg) +* @param yacc Y acceleration (mg) +* @param zacc Z acceleration (mg) +*/ +void UAS::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) +{ + if (this->mode & MAV_MODE_FLAG_HIL_ENABLED) + { + mavlink_message_t msg; + mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, + time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, + lat, lon, alt, vx, vy, vz, xacc, yacc, zacc); + sendMessage(msg); + } + else + { + // Attempt to set HIL mode + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode); + sendMessage(msg); + qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable."; + } +} + +/** +* Connect flight gear link. +**/ +void UAS::startHil() +{ + if (hilEnabled) return; + hilEnabled = true; + // Connect HIL simulation link + simulation->connectSimulation(); + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode); + sendMessage(msg); +} + +/** +* disable flight gear link. +*/ +void UAS::stopHil() +{ + if (simulation) simulation->disconnectSimulation(); + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode); + sendMessage(msg); + hilEnabled = false; +} + +void UAS::shutdown() +{ + bool result = false; + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Critical); + msgBox.setText("Shutting down the UAS"); + msgBox.setInformativeText("Do you want to shut down the onboard computer?"); + + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); + msgBox.setDefaultButton(QMessageBox::Cancel); + int ret = msgBox.exec(); + + // Close the message box shortly after the click to prevent accidental clicks + QTimer::singleShot(5000, &msgBox, SLOT(reject())); + + if (ret == QMessageBox::Yes) + { + // If the active UAS is set, execute command + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0); + sendMessage(msg); + result = true; + } +} + +/** +* @param x position +* @param y position +* @param z position +* @param yaw +*/ +void UAS::setTargetPosition(float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 1, 0, yaw, x, y, z); + sendMessage(msg); +} + +/** + * @return The name of this system as string in human-readable form + */ +QString UAS::getUASName(void) const +{ + QString result; + if (name == "") + { + result = tr("MAV ") + result.sprintf("%03d", getUASID()); + } + else + { + result = name; + } + return result; +} + +/** +* @return the state of the uas as a short text. +*/ +const QString& UAS::getShortState() const +{ + return shortStateText; +} + +/** +* The mode can be autonomous, guided, manual or armed. It will also return if +* hardware in the loop is being used. +* @return the audio mode text for the id given. +*/ +QString UAS::getAudioModeTextFor(int id) +{ + QString mode; + uint8_t modeid = id; + + // BASE MODE DECODING + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) + { + mode += "autonomous"; + } + else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) + { + mode += "guided"; + } + else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) + { + mode += "manual"; + } + else + { + // Nothing else applies, we're in preflight + mode += "preflight"; + } + + if (modeid != 0) + { + mode += " mode"; + } + + // ARMED STATE DECODING + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) + { + mode.append(" and armed"); + } + + // HARDWARE IN THE LOOP DECODING + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL) + { + mode.append(" using hardware in the loop simulation"); + } + + return mode; +} + +/** +* The mode returned can be auto, stabilized, test, manual, preflight or unknown. +* @return the short text of the mode for the id given. +*/ +QString UAS::getShortModeTextFor(int id) +{ + QString mode; + uint8_t modeid = id; + + qDebug() << "MODE:" << modeid; + + // BASE MODE DECODING + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) + { + mode += "AUTO"; + } + else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) + { + mode += "|STABILIZED"; + } +// if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) +// { +// mode += "|STAB"; +// } + else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST) + { + mode += "|TEST"; + } + else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) + { + mode += "|MANUAL"; + } + else if (modeid == 0) + { + mode = "|PREFLIGHT"; + } + else + { + mode = "|UNKNOWN"; + } + + // ARMED STATE DECODING + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) + { + mode.prepend("A"); + } + else + { + mode.prepend("D"); + } + + // HARDWARE IN THE LOOP DECODING + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL) + { + mode.prepend("HIL:"); + } + + return mode; +} + +const QString& UAS::getShortMode() const +{ + return shortModeText; +} + +/** +* Add the link and connect a signal to it which will be set off when it is destroyed. +*/ +void UAS::addLink(LinkInterface* link) +{ + if (!links->contains(link)) + { + links->append(link); + connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*))); + } +} + +void UAS::removeLink(QObject* object) +{ + LinkInterface* link = dynamic_cast(object); + if (link) + { + links->removeAt(links->indexOf(link)); + } +} + +/** +* @return the list of links +*/ +QList* UAS::getLinks() +{ + return links; +} + +/** +* @rerturn the map of the components +*/ +QMap UAS::getComponents() +{ + return components; +} + +/** +* Set the battery type and the number of cells. +* @param type of the battery +* @param cells Number of cells. +*/ +void UAS::setBattery(BatteryType type, int cells) +{ + this->batteryType = type; + this->cells = cells; + switch (batteryType) + { + case NICD: + break; + case NIMH: + break; + case LIION: + break; + case LIPOLY: + fullVoltage = this->cells * UAS::lipoFull; + emptyVoltage = this->cells * UAS::lipoEmpty; + break; + case LIFE: + break; + case AGZN: + break; + } +} + +/** +* Set the battery specificaitons: empty voltage, warning voltage, and full voltage. +* @param specifications of the battery +*/ +void UAS::setBatterySpecs(const QString& specs) +{ + if (specs.length() == 0 || specs.contains("%")) + { + batteryRemainingEstimateEnabled = false; + bool ok; + QString percent = specs; + percent = percent.remove("%"); + float temp = percent.toFloat(&ok); + if (ok) + { + warnLevelPercent = temp; + } + else + { + emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong"); + } + } + else + { + batteryRemainingEstimateEnabled = true; + QString stringList = specs; + stringList = stringList.remove("V"); + stringList = stringList.remove("v"); + QStringList parts = stringList.split(","); + if (parts.length() == 3) + { + float temp; + bool ok; + // Get the empty voltage + temp = parts.at(0).toFloat(&ok); + if (ok) emptyVoltage = temp; + // Get the warning voltage + temp = parts.at(1).toFloat(&ok); + if (ok) warnVoltage = temp; + // Get the full voltage + temp = parts.at(2).toFloat(&ok); + if (ok) fullVoltage = temp; + } + else + { + emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong"); + } + } +} + +/** +* @return the battery specifications(empty voltage, warning voltage, full voltage) +*/ +QString UAS::getBatterySpecs() +{ + if (batteryRemainingEstimateEnabled) + { + return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage); + } + else + { + return QString("%1%").arg(warnLevelPercent); + } +} + +/** +* @return the time remaining. +*/ +int UAS::calculateTimeRemaining() +{ + quint64 dt = QGC::groundTimeMilliseconds() - startTime; + double seconds = dt / 1000.0f; + double voltDifference = startVoltage - currentVoltage; + if (voltDifference <= 0) voltDifference = 0.00000000001f; + double dischargePerSecond = voltDifference / seconds; + int remaining = static_cast((currentVoltage - emptyVoltage) / dischargePerSecond); + // Can never be below 0 + if (remaining < 0) remaining = 0; + return remaining; +} + +/** + * @return charge level in percent - 0 - 100 + */ +float UAS::getChargeLevel() +{ + if (batteryRemainingEstimateEnabled) + { + if (lpVoltage < emptyVoltage) + { + chargeLevel = 0.0f; + } + else if (lpVoltage > fullVoltage) + { + chargeLevel = 100.0f; + } + else + { + chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage)); + } + } + return chargeLevel; +} + +void UAS::startLowBattAlarm() +{ + if (!lowBattAlarm) + { + GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName())); + QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency())); + lowBattAlarm = true; + } +} + +void UAS::stopLowBattAlarm() +{ + if (lowBattAlarm) + { + GAudioOutput::instance()->stopEmergency(); + lowBattAlarm = false; + } +} diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 478edf60b7a5fa4645c67b01d1f01bda26d62b08..e6d6c1b2e8dd242e8a65d2f6e69a3ea051cd6d37 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -1,707 +1,710 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief Definition of Unmanned Aerial Vehicle object - * - * @author Lorenz Meier - * - */ - -#ifndef _UAS_H_ -#define _UAS_H_ - -#include "UASInterface.h" -#include -#include -#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 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* 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* links; ///< List of links this UAS can be reached by - QList 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 actuatorValues; - QList actuatorNames; - - QList motorValues; - QList motorNames; - QMap 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* > 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 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 getParameterNames(int component); - - /** @brief Get the ids of all components */ - QList 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 + +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 . + +======================================================================*/ + +/** + * @file + * @brief Definition of Unmanned Aerial Vehicle object + * + * @author Lorenz Meier + * + */ + +#ifndef _UAS_H_ +#define _UAS_H_ + +#include "UASInterface.h" +#include +#include +#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 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* 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* links; ///< List of links this UAS can be reached by + QList 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 actuatorValues; + QList actuatorNames; + + QList motorValues; + QList motorNames; + QMap 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* > 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 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 getParameterNames(int component); + + /** @brief Get the ids of all components */ + QList 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_ diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 6aa4d2fc34ed1a92c326ca075135e9ac13c4d3f5..36f4fd5b26e1b8089bbf3971936731ef12b29c23 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -475,6 +475,7 @@ signals: void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex); /** @brief Emit the new system type */ void systemTypeSet(UASInterface* uas, unsigned int type); + /** @brief Attitude control enabled/disabled */ void attitudeControlEnabled(bool enabled); /** @brief Position 2D control enabled/disabled */ @@ -483,6 +484,30 @@ signals: void positionZControlEnabled(bool enabled); /** @brief Heading control enabled/disabled */ void positionYawControlEnabled(bool enabled); + /** @brief Optical flow status changed */ + void opticalFlowStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Vision based localization status changed */ + void visionLocalizationStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Infrared / Ultrasound status changed */ + void distanceSensorStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Gyroscope status changed */ + void gyroStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Accelerometer status changed */ + void accelStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Magnetometer status changed */ + void magSensorStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Barometer status changed */ + void baroStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Differential pressure / airspeed status changed */ + void airspeedStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Actuator status changed */ + void actuatorStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Laser scanner status changed */ + void laserStatusChanged(bool supported, bool enabled, bool ok); + /** @brief Vicon / Leica Geotracker status changed */ + void groundTruthSensorStatusChanged(bool supported, bool enabled, bool ok); + + /** @brief Value of a remote control channel (raw) */ void remoteControlChannelRawChanged(int channelId, float raw); /** @brief Value of a remote control channel (scaled)*/ diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 5948daeb3e0be9dd920a9e8a724291c9ecac4b54..72b2cb3f6d19a89eafb25b1cbca17a391adccb76 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -123,7 +123,34 @@ HSIDisplay::HSIDisplay(QWidget *parent) : userSetPointSet(false), userXYSetPointSet(false), userZSetPointSet(false), - userYawSetPointSet(false) + userYawSetPointSet(false), + gyroKnown(false), + gyroON(false), + gyroOK(false), + accelKnown(false), + accelON(false), + accelOK(false), + magKnown(false), + magON(false), + magOK(false), + pressureKnown(false), + pressureON(false), + pressureOK(false), + diffPressureKnown(false), + diffPressureON(false), + diffPressureOK(false), + flowKnown(false), + flowON(false), + flowOK(false), + laserKnown(false), + laserON(false), + laserOK(false), + viconKnown(false), + viconON(false), + viconOK(false), + actuatorsKnown(false), + actuatorsON(false), + actuatorsOK(false) { refreshTimer->setInterval(updateInterval); @@ -845,6 +872,16 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) disconnect(this->uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int))); disconnect(this->uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int))); disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float))); + + disconnect(this->uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), this, SLOT(updateGyroStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(accelStatusChanged(bool,bool,bool)), this, SLOT(updateAccelStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), this, SLOT(updateMagSensorStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(baroStatusChanged(bool,bool,bool)), this, SLOT(updateBaroStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), this, SLOT(updateAirspeedStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), this, SLOT(updateOpticalFlowStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(laserStatusChanged(bool,bool,bool)), this, SLOT(updateLaserStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool))); + disconnect(this->uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), this, SLOT(updateActuatorStatus(bool,bool,bool))); } connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool))); @@ -867,6 +904,16 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int))); connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float))); + connect(uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), this, SLOT(updateGyroStatus(bool,bool,bool))); + connect(uas, SIGNAL(accelStatusChanged(bool,bool,bool)), this, SLOT(updateAccelStatus(bool,bool,bool))); + connect(uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), this, SLOT(updateMagSensorStatus(bool,bool,bool))); + connect(uas, SIGNAL(baroStatusChanged(bool,bool,bool)), this, SLOT(updateBaroStatus(bool,bool,bool))); + connect(uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), this, SLOT(updateAirspeedStatus(bool,bool,bool))); + connect(uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), this, SLOT(updateOpticalFlowStatus(bool,bool,bool))); + connect(uas, SIGNAL(laserStatusChanged(bool,bool,bool)), this, SLOT(updateLaserStatus(bool,bool,bool))); + connect(uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool))); + connect(uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), this, SLOT(updateActuatorStatus(bool,bool,bool))); + this->uas = uas; resetMAVState(); diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h index 55490b3a9eca4f16a5cd7a138055b38fac18fc88..c91f24d8e0f98e457652068aabf6d6df9b51f1ba 100644 --- a/src/ui/HSIDisplay.h +++ b/src/ui/HSIDisplay.h @@ -66,6 +66,83 @@ public slots: void updateAttitudeControllerEnabled(bool enabled); void updatePositionXYControllerEnabled(bool enabled); void updatePositionZControllerEnabled(bool enabled); + + /** @brief Optical flow status changed */ + void updateOpticalFlowStatus(bool supported, bool enabled, bool ok) { + if (supported && enabled && ok) { + visionFix = true; + } else { + visionFix = false; + } + } + + /** @brief Vision based localization status changed */ + void updateVisionLocalizationStatus(bool supported, bool enabled, bool ok) { + if (enabled && ok) { + visionFix = true; + } else { + visionFix = false; + } + visionFixKnown = supported; + } + /** @brief Infrared / Ultrasound status changed */ + void updateDistanceSensorStatus(bool supported, bool enabled, bool ok) { + if (enabled && ok) { + iruFix = true; + } else { + iruFix = false; + } + iruFixKnown = supported; + } + /** @brief Gyroscope status changed */ + void updateGyroStatus(bool supported, bool enabled, bool ok) { + gyroKnown = supported; + gyroON = enabled; + gyroOK = ok; + } + /** @brief Accelerometer status changed */ + void updateAccelStatus(bool supported, bool enabled, bool ok) { + accelKnown = supported; + accelON = enabled; + accelOK = ok; + } + /** @brief Magnetometer status changed */ + void updateMagSensorStatus(bool supported, bool enabled, bool ok) { + magKnown = supported; + magON = enabled; + magOK = ok; + } + /** @brief Barometer status changed */ + void updateBaroStatus(bool supported, bool enabled, bool ok) { + pressureKnown = supported; + pressureON = enabled; + pressureOK = ok; + } + /** @brief Differential pressure / airspeed status changed */ + void updateAirspeedStatus(bool supported, bool enabled, bool ok) { + diffPressureKnown = supported; + diffPressureON = enabled; + diffPressureOK = ok; + } + /** @brief Actuator status changed */ + void updateActuatorStatus(bool supported, bool enabled, bool ok) { + actuatorsKnown = supported; + actuatorsON = enabled; + actuatorsOK = ok; + } + /** @brief Laser scanner status changed */ + void updateLaserStatus(bool supported, bool enabled, bool ok) { + laserKnown = supported; + laserON = enabled; + laserOK = ok; + } + /** @brief Vicon / Leica Geotracker status changed */ + void updateGroundTruthSensorStatus(bool supported, bool enabled, bool ok) { + viconKnown = supported; + viconON = enabled; + viconOK = ok; + } + void updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance); /** @brief Heading control enabled/disabled */ void updatePositionYawControllerEnabled(bool enabled); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index da698e4b6de3c808fabfb068d2f686cd1d505ebe..3c41293c002dd781730318a4db197c1549a9ed1a 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -1,1721 +1,1744 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009 - 2011 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief Implementation of class MainWindow - * @author Lorenz Meier - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "QGC.h" -#include "MAVLinkSimulationLink.h" -#include "SerialLink.h" -#include "UDPLink.h" -#include "MAVLinkProtocol.h" -#include "CommConfigurationWindow.h" -#include "QGCWaypointListMulti.h" -#include "MainWindow.h" -#include "JoystickWidget.h" -#include "GAudioOutput.h" -#include "QGCToolWidget.h" -#include "QGCMAVLinkLogPlayer.h" -#include "QGCSettingsWidget.h" -#include "QGCMapTool.h" -#include "MAVLinkDecoder.h" -#include "QGCMAVLinkMessageSender.h" -#include "QGCRGBDView.h" -#include "QGCFirmwareUpdate.h" - -#ifdef QGC_OSG_ENABLED -#include "Q3DWidgetFactory.h" -#endif - -// FIXME Move -#include "PxQuadMAV.h" -#include "SlugsMAV.h" - - -#include "LogCompressor.h" - -MainWindow* MainWindow::instance(QSplashScreen* screen) -{ - static MainWindow* _instance = 0; - if(_instance == 0) - { - _instance = new MainWindow(); - if (screen) connect(_instance, SIGNAL(initStatusChanged(QString)), screen, SLOT(showMessage(QString))); - - /* Set the application as parent to ensure that this object - * will be destroyed when the main application exits */ - //_instance->setParent(qApp); - } - return _instance; -} - -/** -* Create new mainwindow. The constructor instantiates all parts of the user -* interface. It does NOT show the mainwindow. To display it, call the show() -* method. -* -* @see QMainWindow::show() -**/ -MainWindow::MainWindow(QWidget *parent): - QMainWindow(parent), - currentView(VIEW_UNCONNECTED), - currentStyle(QGC_MAINWINDOW_STYLE_INDOOR), - aboutToCloseFlag(false), - changingViewsFlag(false), - centerStackActionGroup(new QActionGroup(this)), - styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"), - autoReconnect(false), - lowPowerMode(false) -{ - hide(); - emit initStatusChanged("Loading UI Settings.."); - loadSettings(); - if (!settings.contains("CURRENT_VIEW")) - { - // Set this view as default view - settings.setValue("CURRENT_VIEW", currentView); - } - else - { - // LOAD THE LAST VIEW - VIEW_SECTIONS currentViewCandidate = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", currentView).toInt(); - if (currentViewCandidate != VIEW_ENGINEER && - currentViewCandidate != VIEW_OPERATOR && - currentViewCandidate != VIEW_PILOT && - currentViewCandidate != VIEW_FULL) - { - currentView = currentViewCandidate; - } - } - - settings.sync(); - - emit initStatusChanged("Loading Style."); - loadStyle(currentStyle); - - emit initStatusChanged("Setting up user interface."); - - // Setup user interface - ui.setupUi(this); - hide(); - - // Set dock options - setDockOptions(AnimatedDocks | AllowTabbedDocks | AllowNestedDocks); - statusBar()->setSizeGripEnabled(true); - - configureWindowName(); - - // Setup corners - setCorner(Qt::BottomRightCorner, Qt::RightDockWidgetArea); - - // Setup UI state machines - centerStackActionGroup->setExclusive(true); - - centerStack = new QStackedWidget(this); - setCentralWidget(centerStack); - - // Load Toolbar - toolBar = new QGCToolBar(this); - this->addToolBar(toolBar); - // Add actions - toolBar->addPerspectiveChangeAction(ui.actionOperatorsView); - toolBar->addPerspectiveChangeAction(ui.actionEngineersView); - toolBar->addPerspectiveChangeAction(ui.actionPilotsView); - - emit initStatusChanged("Building common widgets."); - - buildCommonWidgets(); - connectCommonWidgets(); - - emit initStatusChanged("Building common actions."); - - // Create actions - connectCommonActions(); - - // Populate link menu - emit initStatusChanged("Populating link menu"); - QList links = LinkManager::instance()->getLinks(); - foreach(LinkInterface* link, links) - { - this->addLink(link); - } - - connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addLink(LinkInterface*))); - - // Connect user interface devices - emit initStatusChanged("Initializing joystick interface."); - joystickWidget = 0; - joystick = new JoystickInput(); - - // Connect link - if (autoReconnect) - { - SerialLink* link = new SerialLink(); - // Add to registry - LinkManager::instance()->add(link); - LinkManager::instance()->addProtocol(link, mavlink); - link->connect(); - } - - // Set low power mode - enableLowPowerMode(lowPowerMode); - - // Initialize window state - windowStateVal = windowState(); - - emit initStatusChanged("Restoring last view state."); - - // Restore the window setup - loadViewState(); - - emit initStatusChanged("Restoring last window size."); - // Restore the window position and size - if (settings.contains(getWindowGeometryKey())) - { - // Restore the window geometry - restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray()); - show(); - } - else - { - // Adjust the size - const int screenWidth = QApplication::desktop()->width(); - const int screenHeight = QApplication::desktop()->height(); - - if (screenWidth < 1200) - { - showFullScreen(); - } - else - { - resize(screenWidth*0.67f, qMin(screenHeight, (int)(screenWidth*0.67f*0.67f))); - show(); - } - - } - - connect(&windowNameUpdateTimer, SIGNAL(timeout()), this, SLOT(configureWindowName())); - windowNameUpdateTimer.start(15000); - emit initStatusChanged("Done."); - show(); -} - -MainWindow::~MainWindow() -{ - if (mavlink) - { - delete mavlink; - mavlink = NULL; - } -// if (simulationLink) -// { -// simulationLink->deleteLater(); -// simulationLink = NULL; -// } - if (joystick) - { - delete joystick; - joystick = NULL; - } - - // Get and delete all dockwidgets and contained - // widgets - QObjectList childList(this->children()); - - QObjectList::iterator i; - QDockWidget* dockWidget; - for (i = childList.begin(); i != childList.end(); ++i) - { - dockWidget = dynamic_cast(*i); - if (dockWidget) - { - // Remove dock widget from main window - // removeDockWidget(dockWidget); - // delete dockWidget->widget(); - delete dockWidget; - dockWidget = NULL; - } - else if (dynamic_cast(*i)) - { - delete dynamic_cast(*i); - *i = NULL; - } - } - // Delete all UAS objects -} - -void MainWindow::resizeEvent(QResizeEvent * event) -{ - if (height() < 800) - { - ui.statusBar->setVisible(false); - } - else - { - ui.statusBar->setVisible(true); - ui.statusBar->setSizeGripEnabled(true); - } - - if (width() > 1200) - { - toolBar->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); - } - else - { - toolBar->setToolButtonStyle(Qt::ToolButtonIconOnly); - } - - QMainWindow::resizeEvent(event); -} - -QString MainWindow::getWindowStateKey() -{ - return QString::number(currentView)+"_windowstate"; -} - -QString MainWindow::getWindowGeometryKey() -{ - //return QString::number(currentView)+"_geometry"; - return "_geometry"; -} - -void MainWindow::buildCustomWidget() -{ - // Create custom widgets - QList widgets = QGCToolWidget::createWidgetsFromSettings(this); - - if (widgets.size() > 0) - { - ui.menuTools->addSeparator(); - } - - for(int i = 0; i < widgets.size(); ++i) - { - // Check if this widget already has a parent, do not create it in this case - QGCToolWidget* tool = widgets.at(i); - QDockWidget* dock = dynamic_cast(tool->parentWidget()); - if (!dock) - { - QDockWidget* dock = new QDockWidget(tool->windowTitle(), this); - dock->setObjectName(tool->objectName()+"_DOCK"); - dock->setWidget(tool); - connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); - QAction* showAction = new QAction(widgets.at(i)->windowTitle(), this); - showAction->setCheckable(true); - connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); - connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); - widgets.at(i)->setMainMenuAction(showAction); - ui.menuTools->addAction(showAction); - - // Load dock widget location (default is bottom) - Qt::DockWidgetArea location = static_cast (tool->getDockWidgetArea(currentView)); - - addDockWidget(location, dock); - } - } -} - -void MainWindow::buildCommonWidgets() -{ - //TODO: move protocol outside UI - mavlink = new MAVLinkProtocol(); - connect(mavlink, SIGNAL(protocolStatusMessage(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection); - // Add generic MAVLink decoder - mavlinkDecoder = new MAVLinkDecoder(mavlink, this); - - // Dock widgets - if (!controlDockWidget) - { - controlDockWidget = new QDockWidget(tr("Control"), this); - controlDockWidget->setObjectName("UNMANNED_SYSTEM_CONTROL_DOCKWIDGET"); - controlDockWidget->setWidget( new UASControlWidget(this) ); - addTool(controlDockWidget, tr("Control"), Qt::LeftDockWidgetArea); - } - - if (!listDockWidget) - { - listDockWidget = new QDockWidget(tr("Unmanned Systems"), this); - listDockWidget->setWidget( new UASListWidget(this) ); - listDockWidget->setObjectName("UNMANNED_SYSTEMS_LIST_DOCKWIDGET"); - addTool(listDockWidget, tr("Unmanned Systems"), Qt::RightDockWidgetArea); - } - - if (!waypointsDockWidget) - { - waypointsDockWidget = new QDockWidget(tr("Mission Plan"), this); - waypointsDockWidget->setWidget( new QGCWaypointListMulti(this) ); - waypointsDockWidget->setObjectName("WAYPOINT_LIST_DOCKWIDGET"); - addTool(waypointsDockWidget, tr("Mission Plan"), Qt::BottomDockWidgetArea); - } - - if (!infoDockWidget) - { - infoDockWidget = new QDockWidget(tr("Status Details"), this); - infoDockWidget->setWidget( new UASInfoWidget(this) ); - infoDockWidget->setObjectName("UAS_STATUS_DETAILS_DOCKWIDGET"); - addTool(infoDockWidget, tr("Status Details"), Qt::RightDockWidgetArea); - } - - if (!debugConsoleDockWidget) - { - debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this); - debugConsoleDockWidget->setWidget( new DebugConsole(this) ); - debugConsoleDockWidget->setObjectName("COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET"); - - DebugConsole *debugConsole = dynamic_cast(debugConsoleDockWidget->widget()); - connect(mavlinkDecoder, SIGNAL(textMessageReceived(int, int, int, const QString)), debugConsole, SLOT(receiveTextMessage(int, int, int, const QString))); - - addTool(debugConsoleDockWidget, tr("Communication Console"), Qt::BottomDockWidgetArea); - } - - if (!logPlayerDockWidget) - { - logPlayerDockWidget = new QDockWidget(tr("MAVLink Log Player"), this); - logPlayer = new QGCMAVLinkLogPlayer(mavlink, this); - toolBar->setLogPlayer(logPlayer); - logPlayerDockWidget->setWidget(logPlayer); - logPlayerDockWidget->setObjectName("MAVLINK_LOG_PLAYER_DOCKWIDGET"); - addTool(logPlayerDockWidget, tr("MAVLink Log Replay"), Qt::RightDockWidgetArea); - } - - if (!mavlinkInspectorWidget) - { - mavlinkInspectorWidget = new QDockWidget(tr("MAVLink Message Inspector"), this); - mavlinkInspectorWidget->setWidget( new QGCMAVLinkInspector(mavlink, this) ); - mavlinkInspectorWidget->setObjectName("MAVLINK_INSPECTOR_DOCKWIDGET"); - addTool(mavlinkInspectorWidget, tr("MAVLink Inspector"), Qt::RightDockWidgetArea); - } - - if (!mavlinkSenderWidget) - { -// mavlinkSenderWidget = new QDockWidget(tr("MAVLink Message Sender"), this); -// mavlinkSenderWidget->setWidget( new QGCMAVLinkMessageSender(mavlink, this) ); -// mavlinkSenderWidget->setObjectName("MAVLINK_SENDER_DOCKWIDGET"); -// addTool(mavlinkSenderWidget, tr("MAVLink Sender"), Qt::RightDockWidgetArea); - } - - //FIXME: memory of acceptList will never be freed again - QStringList* acceptList = new QStringList(); - acceptList->append("-3.3,ATTITUDE.roll,rad,+3.3,s"); - acceptList->append("-3.3,ATTITUDE.pitch,deg,+3.3,s"); - acceptList->append("-3.3,ATTITUDE.yaw,deg,+3.3,s"); - - //FIXME: memory of acceptList2 will never be freed again - QStringList* acceptList2 = new QStringList(); - acceptList2->append("0,RAW_PRESSURE.pres_abs,hPa,65500"); - - if (!parametersDockWidget) - { - parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this); - parametersDockWidget->setWidget( new ParameterInterface(this) ); - parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET"); - addTool(parametersDockWidget, tr("Onboard Parameters"), Qt::RightDockWidgetArea); - } - - if (!hsiDockWidget) - { - hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this); - hsiDockWidget->setWidget( new HSIDisplay(this) ); - hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET"); - addTool(hsiDockWidget, tr("Horizontal Situation"), Qt::BottomDockWidgetArea); - } - - if (!headDown1DockWidget) - { - headDown1DockWidget = new QDockWidget(tr("Flight Display"), this); - HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this); - hdDisplay->addSource(mavlinkDecoder); - headDown1DockWidget->setWidget(hdDisplay); - headDown1DockWidget->setObjectName("HEAD_DOWN_DISPLAY_1_DOCK_WIDGET"); - addTool(headDown1DockWidget, tr("Flight Display"), Qt::RightDockWidgetArea); - } - - if (!headDown2DockWidget) - { - headDown2DockWidget = new QDockWidget(tr("Actuator Status"), this); - HDDisplay* hdDisplay = new HDDisplay(acceptList2, "Actuator Status", this); - hdDisplay->addSource(mavlinkDecoder); - headDown2DockWidget->setWidget(hdDisplay); - headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET"); - addTool(headDown2DockWidget, tr("Actuator Status"), Qt::RightDockWidgetArea); - } - - if (!rcViewDockWidget) - { - rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); - rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); - rcViewDockWidget->setObjectName("RADIO_CONTROL_CHANNELS_DOCK_WIDGET"); - addTool(rcViewDockWidget, tr("Radio Control"), Qt::BottomDockWidgetArea); - } - - if (!headUpDockWidget) - { - headUpDockWidget = new QDockWidget(tr("HUD"), this); - headUpDockWidget->setWidget( new HUD(320, 240, this)); - headUpDockWidget->setObjectName("HEAD_UP_DISPLAY_DOCK_WIDGET"); - addTool(headUpDockWidget, tr("Head Up Display"), Qt::RightDockWidgetArea); - } - - if (!video1DockWidget) - { - video1DockWidget = new QDockWidget(tr("Video Stream 1"), this); - QGCRGBDView* video1 = new QGCRGBDView(160, 120, this); - video1->enableHUDInstruments(false); - video1->enableVideo(false); - // FIXME select video stream as well - video1DockWidget->setWidget(video1); - video1DockWidget->setObjectName("VIDEO_STREAM_1_DOCK_WIDGET"); - addTool(video1DockWidget, tr("Video Stream 1"), Qt::LeftDockWidgetArea); - } - - if (!video2DockWidget) - { - video2DockWidget = new QDockWidget(tr("Video Stream 2"), this); - QGCRGBDView* video2 = new QGCRGBDView(160, 120, this); - video2->enableHUDInstruments(false); - video2->enableVideo(false); - // FIXME select video stream as well - video2DockWidget->setWidget(video2); - video2DockWidget->setObjectName("VIDEO_STREAM_2_DOCK_WIDGET"); - addTool(video2DockWidget, tr("Video Stream 2"), Qt::LeftDockWidgetArea); - } - -// if (!rgbd1DockWidget) { -// rgbd1DockWidget = new QDockWidget(tr("Video Stream 1"), this); -// HUD* video1 = new HUD(160, 120, this); -// video1->enableHUDInstruments(false); -// video1->enableVideo(true); -// // FIXME select video stream as well -// video1DockWidget->setWidget(video1); -// video1DockWidget->setObjectName("VIDEO_STREAM_1_DOCK_WIDGET"); -// addTool(video1DockWidget, tr("Video Stream 1"), Qt::LeftDockWidgetArea); -// } - -// if (!rgbd2DockWidget) { -// video2DockWidget = new QDockWidget(tr("Video Stream 2"), this); -// HUD* video2 = new HUD(160, 120, this); -// video2->enableHUDInstruments(false); -// video2->enableVideo(true); -// // FIXME select video stream as well -// video2DockWidget->setWidget(video2); -// video2DockWidget->setObjectName("VIDEO_STREAM_2_DOCK_WIDGET"); -// addTool(video2DockWidget, tr("Video Stream 2"), Qt::LeftDockWidgetArea); -// } - - // Custom widgets, added last to all menus and layouts - buildCustomWidget(); - - // Center widgets - if (!mapWidget) - { - mapWidget = new QGCMapTool(this); - addCentralWidget(mapWidget, "Maps"); - } - - if (!protocolWidget) - { - protocolWidget = new XMLCommProtocolWidget(this); - addCentralWidget(protocolWidget, "Mavlink Generator"); - } - -// if (!firmwareUpdateWidget) -// { -// firmwareUpdateWidget = new QGCFirmwareUpdate(this); -// addCentralWidget(firmwareUpdateWidget, "Firmware Update"); -// } - - if (!hudWidget) - { - hudWidget = new HUD(320, 240, this); - addCentralWidget(hudWidget, tr("Head Up Display")); - } - - if (!configWidget) - { - configWidget = new QGCVehicleConfig(this); - addCentralWidget(configWidget, tr("Vehicle Configuration")); - } - - if (!dataplotWidget) - { - dataplotWidget = new QGCDataPlot2D(this); - addCentralWidget(dataplotWidget, tr("Logfile Plot")); - } - -#ifdef QGC_OSG_ENABLED - if (!_3DWidget) - { - _3DWidget = Q3DWidgetFactory::get("PIXHAWK", this); - addCentralWidget(_3DWidget, tr("Local 3D")); - } -#endif - -#if (defined _MSC_VER) | (defined Q_OS_MAC) - if (!gEarthWidget) - { - gEarthWidget = new QGCGoogleEarthView(this); - addCentralWidget(gEarthWidget, tr("Google Earth")); - } -#endif -} - -void MainWindow::addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea area) -{ - QAction* tempAction = ui.menuTools->addAction(title); - - tempAction->setCheckable(true); - QVariant var; - var.setValue((QWidget*)widget); - tempAction->setData(var); - connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); - connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool))); - tempAction->setChecked(widget->isVisible()); - addDockWidget(area, widget); -} - - -void MainWindow::showTool(bool show) -{ - QAction* act = qobject_cast(sender()); - QWidget* widget = qVariantValue(act->data()); - widget->setVisible(show); -} - -void MainWindow::addCentralWidget(QWidget* widget, const QString& title) -{ - // Check if this widget already has been added - if (centerStack->indexOf(widget) == -1) - { - centerStack->addWidget(widget); - - QAction* tempAction = ui.menuMain->addAction(title); - - tempAction->setCheckable(true); - QVariant var; - var.setValue((QWidget*)widget); - tempAction->setData(var); - centerStackActionGroup->addAction(tempAction); - connect(tempAction,SIGNAL(triggered()),this, SLOT(showCentralWidget())); - connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool))); - tempAction->setChecked(widget->isVisible()); - } -} - - -void MainWindow::showCentralWidget() -{ - QAction* act = qobject_cast(sender()); - QWidget* widget = qVariantValue(act->data()); - centerStack->setCurrentWidget(widget); -} - -void MainWindow::showHILConfigurationWidget(UASInterface* uas) -{ - // Add simulation configuration widget - UAS* mav = dynamic_cast(uas); - - if (mav) - { - QGCHilConfiguration* hconf = new QGCHilConfiguration(mav, this); - QString hilDockName = tr("HIL Config (%1)").arg(uas->getUASName()); - QDockWidget* hilDock = new QDockWidget(hilDockName, this); - hilDock->setWidget(hconf); - hilDock->setObjectName(QString("HIL_CONFIG_%1").arg(uas->getUASID())); - addTool(hilDock, hilDockName, Qt::RightDockWidgetArea); - - } - - // Reload view state in case new widgets were added - loadViewState(); -} - -void MainWindow::closeEvent(QCloseEvent *event) -{ - if (isVisible()) storeViewState(); - storeSettings(); - aboutToCloseFlag = true; - mavlink->storeSettings(); - UASManager::instance()->storeSettings(); - QMainWindow::closeEvent(event); -} - -/** - * Connect the signals and slots of the common window widgets - */ -void MainWindow::connectCommonWidgets() -{ - if (infoDockWidget && infoDockWidget->widget()) - { - connect(mavlink, SIGNAL(receiveLossChanged(int, float)), - infoDockWidget->widget(), SLOT(updateSendLoss(int, float))); - } -} - -void MainWindow::createCustomWidget() -{ - QDockWidget* dock = new QDockWidget("Unnamed Tool", this); - QGCToolWidget* tool = new QGCToolWidget("Unnamed Tool", dock); - - if (QGCToolWidget::instances()->size() < 2) - { - // This is the first widget - ui.menuTools->addSeparator(); - } - - connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); - dock->setWidget(tool); - - QAction* showAction = new QAction(tool->getTitle(), this); - showAction->setCheckable(true); - connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); - connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); - tool->setMainMenuAction(showAction); - ui.menuTools->addAction(showAction); - this->addDockWidget(Qt::BottomDockWidgetArea, dock); - dock->setVisible(true); -} - -void MainWindow::loadCustomWidget() -{ - QString widgetFileExtension(".qgw"); - QString fileName = QFileDialog::getOpenFileName(this, tr("Specify Widget File Name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("QGroundControl Widget (*%1);;").arg(widgetFileExtension)); - if (fileName != "") loadCustomWidget(fileName); -} - -void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) -{ - QGCToolWidget* tool = new QGCToolWidget("", this); - if (tool->loadSettings(fileName, true) || !singleinstance) - { - // Add widget to UI - QDockWidget* dock = new QDockWidget(tool->getTitle(), this); - connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); - dock->setWidget(tool); - tool->setParent(dock); - - QAction* showAction = new QAction(tool->getTitle(), this); - showAction->setCheckable(true); - connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); - connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); - tool->setMainMenuAction(showAction); - ui.menuTools->addAction(showAction); - this->addDockWidget(Qt::BottomDockWidgetArea, dock); - dock->setVisible(true); - } - else - { - return; - } -} - -void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType) -{ - QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/widgets/"; - QString platformDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; - - QDir widgets(defaultsDir); - QStringList files = widgets.entryList(); - QDir platformWidgets(platformDir); - files.append(platformWidgets.entryList()); - - if (files.count() == 0) - { - qDebug() << "No default custom widgets for system " << systemType << "autopilot" << autopilotType << " found"; - qDebug() << "Tried with path: " << defaultsDir; - showStatusMessage(tr("Did not find any custom widgets in %1").arg(defaultsDir)); - } - - // Load all custom widgets found in the AP folder - for(int i = 0; i < files.count(); ++i) - { - QString file = files[i]; - if (file.endsWith(".qgw")) - { - // Will only be loaded if not already a custom widget with - // the same name is present - loadCustomWidget(defaultsDir+"/"+file, true); - showStatusMessage(tr("Loaded custom widget %1").arg(defaultsDir+"/"+file)); - } - } -} - -void MainWindow::loadSettings() -{ - QSettings settings; - settings.beginGroup("QGC_MAINWINDOW"); - autoReconnect = settings.value("AUTO_RECONNECT", autoReconnect).toBool(); - currentStyle = (QGC_MAINWINDOW_STYLE)settings.value("CURRENT_STYLE", currentStyle).toInt(); - lowPowerMode = settings.value("LOW_POWER_MODE", lowPowerMode).toBool(); - settings.endGroup(); -} - -void MainWindow::storeSettings() -{ - QSettings settings; - settings.beginGroup("QGC_MAINWINDOW"); - settings.setValue("AUTO_RECONNECT", autoReconnect); - settings.setValue("CURRENT_STYLE", currentStyle); - settings.endGroup(); - if (!aboutToCloseFlag && isVisible()) - { - settings.setValue(getWindowGeometryKey(), saveGeometry()); - // Save the last current view in any case - settings.setValue("CURRENT_VIEW", currentView); - // Save the current window state, but only if a system is connected (else no real number of widgets would be present) - if (UASManager::instance()->getUASList().length() > 0) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); - // Save the current view only if a UAS is connected - if (UASManager::instance()->getUASList().length() > 0) settings.setValue("CURRENT_VIEW_WITH_UAS_CONNECTED", currentView); - // Save the current power mode - } - settings.setValue("LOW_POWER_MODE", lowPowerMode); - settings.sync(); -} - -void MainWindow::configureWindowName() -{ - QList hostAddresses = QNetworkInterface::allAddresses(); - QString windowname = qApp->applicationName() + " " + qApp->applicationVersion(); - bool prevAddr = false; - - windowname.append(" (" + QHostInfo::localHostName() + ": "); - - for (int i = 0; i < hostAddresses.size(); i++) - { - // Exclude loopback IPv4 and all IPv6 addresses - if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":")) - { - if(prevAddr) windowname.append("/"); - windowname.append(hostAddresses.at(i).toString()); - prevAddr = true; - } - } - - windowname.append(")"); - - setWindowTitle(windowname); - -#ifndef Q_WS_MAC - //qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png")); -#endif -} - -void MainWindow::startVideoCapture() -{ - QString format = "bmp"; - QString initialPath = QDir::currentPath() + tr("/untitled.") + format; - - QString screenFileName = QFileDialog::getSaveFileName(this, tr("Save As"), - initialPath, - tr("%1 Files (*.%2);;All Files (*)") - .arg(format.toUpper()) - .arg(format)); - delete videoTimer; - videoTimer = new QTimer(this); - //videoTimer->setInterval(40); - //connect(videoTimer, SIGNAL(timeout()), this, SLOT(saveScreen())); - //videoTimer->stop(); -} - -void MainWindow::stopVideoCapture() -{ - videoTimer->stop(); - - // TODO Convert raw images to PNG -} - -void MainWindow::saveScreen() -{ - QPixmap window = QPixmap::grabWindow(this->winId()); - QString format = "bmp"; - - if (!screenFileName.isEmpty()) - { - window.save(screenFileName, format.toAscii()); - } -} - -void MainWindow::enableAutoReconnect(bool enabled) -{ - autoReconnect = enabled; -} - -void MainWindow::loadNativeStyle() -{ - loadStyle(QGC_MAINWINDOW_STYLE_NATIVE); -} - -void MainWindow::loadIndoorStyle() -{ - loadStyle(QGC_MAINWINDOW_STYLE_INDOOR); -} - -void MainWindow::loadOutdoorStyle() -{ - loadStyle(QGC_MAINWINDOW_STYLE_OUTDOOR); -} - -void MainWindow::loadStyle(QGC_MAINWINDOW_STYLE style) -{ - switch (style) { - case QGC_MAINWINDOW_STYLE_NATIVE: { - // Native mode means setting no style - // so if we were already in native mode - // take no action - // Only if a style was set, remove it. - if (style != currentStyle) { - qApp->setStyleSheet(""); - showInfoMessage(tr("Please restart QGroundControl"), tr("Please restart QGroundControl to switch to fully native look and feel. Currently you have loaded Qt's plastique style.")); - } - } - break; - case QGC_MAINWINDOW_STYLE_INDOOR: - qApp->setStyle("plastique"); - styleFileName = ":files/styles/style-indoor.css"; - reloadStylesheet(); - break; - case QGC_MAINWINDOW_STYLE_OUTDOOR: - qApp->setStyle("plastique"); - styleFileName = ":files/styles/style-outdoor.css"; - reloadStylesheet(); - break; - } - currentStyle = style; -} - -void MainWindow::selectStylesheet() -{ - // Let user select style sheet - styleFileName = QFileDialog::getOpenFileName(this, tr("Specify stylesheet"), styleFileName, tr("CSS Stylesheet (*.css);;")); - - if (!styleFileName.endsWith(".css")) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Information); - msgBox.setText(tr("QGroundControl did lot load a new style")); - msgBox.setInformativeText(tr("No suitable .css file selected. Please select a valid .css file.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - return; - } - - // Load style sheet - reloadStylesheet(); -} - -void MainWindow::reloadStylesheet() -{ - // Load style sheet - QFile* styleSheet = new QFile(styleFileName); - if (!styleSheet->exists()) - { - styleSheet = new QFile(":files/styles/style-indoor.css"); - } - if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text)) - { - QString style = QString(styleSheet->readAll()); - style.replace("ICONDIR", QCoreApplication::applicationDirPath()+ "files/styles/"); - qApp->setStyleSheet(style); - } - else - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Information); - msgBox.setText(tr("QGroundControl did lot load a new style")); - msgBox.setInformativeText(tr("Stylesheet file %1 was not readable").arg(styleFileName)); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - } - delete styleSheet; -} - -/** - * The status message will be overwritten if a new message is posted to this function - * - * @param status message text - * @param timeout how long the status should be displayed - */ -void MainWindow::showStatusMessage(const QString& status, int timeout) -{ - statusBar()->showMessage(status, timeout); -} - -/** - * The status message will be overwritten if a new message is posted to this function. - * it will be automatically hidden after 5 seconds. - * - * @param status message text - */ -void MainWindow::showStatusMessage(const QString& status) -{ - statusBar()->showMessage(status, 20000); -} - -void MainWindow::showCriticalMessage(const QString& title, const QString& message) -{ - QMessageBox msgBox(this); - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText(title); - msgBox.setInformativeText(message); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); -} - -void MainWindow::showInfoMessage(const QString& title, const QString& message) -{ - QMessageBox msgBox(this); - msgBox.setIcon(QMessageBox::Information); - msgBox.setText(title); - msgBox.setInformativeText(message); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); -} - -/** -* @brief Create all actions associated to the main window -* -**/ -void MainWindow::connectCommonActions() -{ - // Bind together the perspective actions - QActionGroup* perspectives = new QActionGroup(ui.menuPerspectives); - perspectives->addAction(ui.actionEngineersView); - perspectives->addAction(ui.actionMavlinkView); - perspectives->addAction(ui.actionPilotsView); - perspectives->addAction(ui.actionOperatorsView); - perspectives->addAction(ui.actionFirmwareUpdateView); - perspectives->addAction(ui.actionUnconnectedView); - perspectives->setExclusive(true); - - // Mark the right one as selected - if (currentView == VIEW_ENGINEER) ui.actionEngineersView->setChecked(true); - if (currentView == VIEW_MAVLINK) ui.actionMavlinkView->setChecked(true); - if (currentView == VIEW_PILOT) ui.actionPilotsView->setChecked(true); - if (currentView == VIEW_OPERATOR) ui.actionOperatorsView->setChecked(true); - if (currentView == VIEW_FIRMWAREUPDATE) ui.actionFirmwareUpdateView->setChecked(true); - if (currentView == VIEW_UNCONNECTED) ui.actionUnconnectedView->setChecked(true); - - // The UAS actions are not enabled without connection to system - ui.actionLiftoff->setEnabled(false); - ui.actionLand->setEnabled(false); - ui.actionEmergency_Kill->setEnabled(false); - ui.actionEmergency_Land->setEnabled(false); - ui.actionShutdownMAV->setEnabled(false); - - // Connect actions from ui - connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink())); - - // Connect internal actions - connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*))); - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); - - // Unmanned System controls - connect(ui.actionLiftoff, SIGNAL(triggered()), UASManager::instance(), SLOT(launchActiveUAS())); - connect(ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS())); - connect(ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS())); - connect(ui.actionEmergency_Kill, SIGNAL(triggered()), UASManager::instance(), SLOT(killActiveUAS())); - connect(ui.actionShutdownMAV, SIGNAL(triggered()), UASManager::instance(), SLOT(shutdownActiveUAS())); - connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS())); - - // Views actions - connect(ui.actionPilotsView, SIGNAL(triggered()), this, SLOT(loadPilotView())); - connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView())); - connect(ui.actionOperatorsView, SIGNAL(triggered()), this, SLOT(loadOperatorView())); - connect(ui.actionUnconnectedView, SIGNAL(triggered()), this, SLOT(loadUnconnectedView())); - - connect(ui.actionFirmwareUpdateView, SIGNAL(triggered()), this, SLOT(loadFirmwareUpdateView())); - connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView())); - - connect(ui.actionReloadStylesheet, SIGNAL(triggered()), this, SLOT(reloadStylesheet())); - connect(ui.actionSelectStylesheet, SIGNAL(triggered()), this, SLOT(selectStylesheet())); - - // Help Actions - connect(ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp())); - connect(ui.actionDeveloper_Credits, SIGNAL(triggered()), this, SLOT(showCredits())); - connect(ui.actionProject_Roadmap_2, SIGNAL(triggered()), this, SLOT(showRoadMap())); - - // Custom widget actions - connect(ui.actionNewCustomWidget, SIGNAL(triggered()), this, SLOT(createCustomWidget())); - connect(ui.actionLoadCustomWidgetFile, SIGNAL(triggered()), this, SLOT(loadCustomWidget())); - - // Audio output - ui.actionMuteAudioOutput->setChecked(GAudioOutput::instance()->isMuted()); - connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), ui.actionMuteAudioOutput, SLOT(setChecked(bool))); - connect(ui.actionMuteAudioOutput, SIGNAL(triggered(bool)), GAudioOutput::instance(), SLOT(mute(bool))); - - // User interaction - // NOTE: Joystick thread is not started and - // configuration widget is not instantiated - // unless it is actually used - // so no ressources spend on this. - ui.actionJoystickSettings->setVisible(true); - - // Configuration - // Joystick - connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure())); - // Application Settings - connect(ui.actionSettings, SIGNAL(triggered()), this, SLOT(showSettings())); -} - -void MainWindow::showHelp() -{ - if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/users/start"))) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText("Could not open help in browser"); - msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/user_guide in a browser."); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - } -} - -void MainWindow::showCredits() -{ - if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/credits"))) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText("Could not open credits in browser"); - msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/credits in a browser."); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - } -} - -void MainWindow::showRoadMap() -{ - if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/dev/roadmap"))) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Critical); - msgBox.setText("Could not open roadmap in browser"); - msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/roadmap in a browser."); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - } -} - -void MainWindow::configure() -{ - if (!joystickWidget) - { - if (!joystick->isRunning()) - { - joystick->start(); - } - joystickWidget = new JoystickWidget(joystick); - } - joystickWidget->show(); -} - -void MainWindow::showSettings() -{ - QGCSettingsWidget* settings = new QGCSettingsWidget(this); - settings->show(); -} - -void MainWindow::addLink() -{ - SerialLink* link = new SerialLink(); - // TODO This should be only done in the dialog itself - - LinkManager::instance()->add(link); - LinkManager::instance()->addProtocol(link, mavlink); - - // Go fishing for this link's configuration window - QList actions = ui.menuNetwork->actions(); - - const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link)); - const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId()); - - foreach (QAction* act, actions) - { - if (act->data().toInt() == linkID) - { // LinkManager::instance()->getLinks().indexOf(link) - act->trigger(); - break; - } - } -} - -void MainWindow::addLink(LinkInterface *link) -{ - // IMPORTANT! KEEP THESE TWO LINES - // THEY MAKE SURE THE LINK IS PROPERLY REGISTERED - // BEFORE LINKING THE UI AGAINST IT - // Register (does nothing if already registered) - LinkManager::instance()->add(link); - LinkManager::instance()->addProtocol(link, mavlink); - - // Go fishing for this link's configuration window - QList actions = ui.menuNetwork->actions(); - - bool found(false); - - const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link)); - const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId()); - - foreach (QAction* act, actions) - { - if (act->data().toInt() == linkID) - { // LinkManager::instance()->getLinks().indexOf(link) - found = true; - } - } - - //UDPLink* udp = dynamic_cast(link); - - if (!found) - { // || udp - CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); - QAction* action = commWidget->getAction(); - ui.menuNetwork->addAction(action); - - // Error handling - connect(link, SIGNAL(communicationError(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection); - // Special case for simulationlink - MAVLinkSimulationLink* sim = dynamic_cast(link); - if (sim) - { - connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool))); - } - } -} - -void MainWindow::setActiveUAS(UASInterface* uas) -{ - // Enable and rename menu - ui.menuUnmanned_System->setTitle(uas->getUASName()); - if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true); -} - -void MainWindow::UASSpecsChanged(int uas) -{ - UASInterface* activeUAS = UASManager::instance()->getActiveUAS(); - if (activeUAS) - { - if (activeUAS->getUASID() == uas) - { - ui.menuUnmanned_System->setTitle(activeUAS->getUASName()); - } - } - else - { - // Last system deleted - ui.menuUnmanned_System->setTitle(tr("No System")); - ui.menuUnmanned_System->setEnabled(false); - } -} - -void MainWindow::UASCreated(UASInterface* uas) -{ - - // Connect the UAS to the full user interface - - //if (uas != NULL) - //{ - // The pilot, operator and engineer views were not available on startup, enable them now - ui.actionPilotsView->setEnabled(true); - ui.actionOperatorsView->setEnabled(true); - ui.actionEngineersView->setEnabled(true); - // The UAS actions are not enabled without connection to system - ui.actionLiftoff->setEnabled(true); - ui.actionLand->setEnabled(true); - ui.actionEmergency_Kill->setEnabled(true); - ui.actionEmergency_Land->setEnabled(true); - ui.actionShutdownMAV->setEnabled(true); - - QIcon icon; - // Set matching icon - switch (uas->getSystemType()) - { - case MAV_TYPE_GENERIC: - icon = QIcon(":files/images/mavs/generic.svg"); - break; - case MAV_TYPE_FIXED_WING: - icon = QIcon(":files/images/mavs/fixed-wing.svg"); - break; - case MAV_TYPE_QUADROTOR: - icon = QIcon(":files/images/mavs/quadrotor.svg"); - break; - case MAV_TYPE_COAXIAL: - icon = QIcon(":files/images/mavs/coaxial.svg"); - break; - case MAV_TYPE_HELICOPTER: - icon = QIcon(":files/images/mavs/helicopter.svg"); - break; - case MAV_TYPE_ANTENNA_TRACKER: - icon = QIcon(":files/images/mavs/antenna-tracker.svg"); - break; - case MAV_TYPE_GCS: - icon = QIcon(":files/images/mavs/groundstation.svg"); - break; - case MAV_TYPE_AIRSHIP: - icon = QIcon(":files/images/mavs/airship.svg"); - break; - case MAV_TYPE_FREE_BALLOON: - icon = QIcon(":files/images/mavs/free-balloon.svg"); - break; - case MAV_TYPE_ROCKET: - icon = QIcon(":files/images/mavs/rocket.svg"); - break; - case MAV_TYPE_GROUND_ROVER: - icon = QIcon(":files/images/mavs/ground-rover.svg"); - break; - case MAV_TYPE_SURFACE_BOAT: - icon = QIcon(":files/images/mavs/surface-boat.svg"); - break; - case MAV_TYPE_SUBMARINE: - icon = QIcon(":files/images/mavs/submarine.svg"); - break; - case MAV_TYPE_HEXAROTOR: - icon = QIcon(":files/images/mavs/hexarotor.svg"); - break; - case MAV_TYPE_OCTOROTOR: - icon = QIcon(":files/images/mavs/octorotor.svg"); - break; - case MAV_TYPE_TRICOPTER: - icon = QIcon(":files/images/mavs/tricopter.svg"); - break; - case MAV_TYPE_FLAPPING_WING: - icon = QIcon(":files/images/mavs/flapping-wing.svg"); - break; - case MAV_TYPE_KITE: - icon = QIcon(":files/images/mavs/kite.svg"); - break; - default: - icon = QIcon(":files/images/mavs/unknown.svg"); - break; - } - - QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems); - connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater())); - connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected())); - connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int))); - - ui.menuConnected_Systems->addAction(uasAction); - - // FIXME Should be not inside the mainwindow - if (debugConsoleDockWidget) - { - DebugConsole *debugConsole = dynamic_cast(debugConsoleDockWidget->widget()); - if (debugConsole) - { - connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), - debugConsole, SLOT(receiveTextMessage(int,int,int,QString))); - } - } - - // Health / System status indicator - if (infoDockWidget) - { - UASInfoWidget *infoWidget = dynamic_cast(infoDockWidget->widget()); - if (infoWidget) - { - infoWidget->addUAS(uas); - } - } - - // UAS List - if (listDockWidget) - { - UASListWidget *listWidget = dynamic_cast(listDockWidget->widget()); - if (listWidget) - { - listWidget->addUAS(uas); - } - } - - // Line chart - if (!linechartWidget) - { - // Center widgets - linechartWidget = new Linecharts(this); - linechartWidget->addSource(mavlinkDecoder); - addCentralWidget(linechartWidget, tr("Realtime Plot")); - } - - // Load default custom widgets for this autopilot type - loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName()); - - - if (uas->getAutopilotType() == MAV_AUTOPILOT_PIXHAWK) - { - // Dock widgets - if (!detectionDockWidget) - { - detectionDockWidget = new QDockWidget(tr("Object Recognition"), this); - detectionDockWidget->setWidget( new ObjectDetectionView("files/images/patterns", this) ); - detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET"); - addTool(detectionDockWidget, tr("Object Recognition"), Qt::RightDockWidgetArea); - } - - if (!watchdogControlDockWidget) - { - watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this); - watchdogControlDockWidget->setWidget( new WatchdogControl(this) ); - watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET"); - addTool(watchdogControlDockWidget, tr("Process Control"), Qt::BottomDockWidgetArea); - } - } - - // Change the view only if this is the first UAS - - // If this is the first connected UAS, it is both created as well as - // the currently active UAS - if (UASManager::instance()->getUASList().size() == 1) - { - // Load last view if setting is present - if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED")) - { - int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt(); - switch (view) - { - case VIEW_ENGINEER: - loadEngineerView(); - break; - case VIEW_MAVLINK: - loadMAVLinkView(); - break; - case VIEW_FIRMWAREUPDATE: - loadFirmwareUpdateView(); - break; - case VIEW_PILOT: - loadPilotView(); - break; - case VIEW_UNCONNECTED: - loadUnconnectedView(); - break; - case VIEW_OPERATOR: - default: - loadOperatorView(); - break; - } - } - else - { - loadOperatorView(); - } - } - - //} - - if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true); - if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true); - - // Reload view state in case new widgets were added - loadViewState(); -} - -void MainWindow::UASDeleted(UASInterface* uas) -{ - if (UASManager::instance()->getUASList().count() == 0) - { - // Last system deleted - ui.menuUnmanned_System->setTitle(tr("No System")); - ui.menuUnmanned_System->setEnabled(false); - } - - QAction* act; - QList actions = ui.menuConnected_Systems->actions(); - - foreach (act, actions) - { - if (act->text().contains(uas->getUASName())) - ui.menuConnected_Systems->removeAction(act); - } -} - -/** - * Stores the current view state - */ -void MainWindow::storeViewState() -{ - if (!aboutToCloseFlag) - { - // Save current state - settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); - settings.setValue(getWindowStateKey()+"CENTER_WIDGET", centerStack->currentIndex()); - // Although we want save the state of the window, we do not want to change the top-leve state (minimized, maximized, etc) - // therefore this state is stored here and restored after applying the rest of the settings in the new - // perspective. - windowStateVal = this->windowState(); - settings.setValue(getWindowGeometryKey(), saveGeometry()); - } -} - -void MainWindow::loadViewState() -{ - // Restore center stack state - int index = settings.value(getWindowStateKey()+"CENTER_WIDGET", -1).toInt(); - // The offline plot view is usually the consequence of a logging run, always show the realtime view first - if (centerStack->indexOf(dataplotWidget) == index) - { - // Rewrite to realtime plot - index = centerStack->indexOf(linechartWidget); - } - - if (index != -1) - { - centerStack->setCurrentIndex(index); - } - else - { - // Hide custom widgets - if (detectionDockWidget) detectionDockWidget->hide(); - if (watchdogControlDockWidget) watchdogControlDockWidget->hide(); - - // Load defaults - switch (currentView) - { - case VIEW_ENGINEER: - centerStack->setCurrentWidget(linechartWidget); - controlDockWidget->hide(); - listDockWidget->hide(); - waypointsDockWidget->hide(); - infoDockWidget->hide(); - debugConsoleDockWidget->show(); - logPlayerDockWidget->show(); - mavlinkInspectorWidget->show(); - //mavlinkSenderWidget->show(); - parametersDockWidget->show(); - hsiDockWidget->hide(); - headDown1DockWidget->hide(); - headDown2DockWidget->hide(); - rcViewDockWidget->hide(); - headUpDockWidget->hide(); - video1DockWidget->hide(); - video2DockWidget->hide(); - break; - case VIEW_PILOT: - centerStack->setCurrentWidget(hudWidget); - controlDockWidget->hide(); - listDockWidget->hide(); - waypointsDockWidget->hide(); - infoDockWidget->hide(); - debugConsoleDockWidget->hide(); - logPlayerDockWidget->hide(); - mavlinkInspectorWidget->hide(); - parametersDockWidget->hide(); - hsiDockWidget->show(); - headDown1DockWidget->show(); - headDown2DockWidget->show(); - rcViewDockWidget->hide(); - headUpDockWidget->hide(); - video1DockWidget->hide(); - video2DockWidget->hide(); - break; - case VIEW_MAVLINK: - centerStack->setCurrentWidget(protocolWidget); - controlDockWidget->hide(); - listDockWidget->hide(); - waypointsDockWidget->hide(); - infoDockWidget->hide(); - debugConsoleDockWidget->hide(); - logPlayerDockWidget->hide(); - mavlinkInspectorWidget->show(); - //mavlinkSenderWidget->show(); - parametersDockWidget->hide(); - hsiDockWidget->hide(); - headDown1DockWidget->hide(); - headDown2DockWidget->hide(); - rcViewDockWidget->hide(); - headUpDockWidget->hide(); - video1DockWidget->hide(); - video2DockWidget->hide(); - break; - case VIEW_FIRMWAREUPDATE: - centerStack->setCurrentWidget(firmwareUpdateWidget); - controlDockWidget->hide(); - listDockWidget->hide(); - waypointsDockWidget->hide(); - infoDockWidget->hide(); - debugConsoleDockWidget->hide(); - logPlayerDockWidget->hide(); - mavlinkInspectorWidget->hide(); - //mavlinkSenderWidget->hide(); - parametersDockWidget->hide(); - hsiDockWidget->hide(); - headDown1DockWidget->hide(); - headDown2DockWidget->hide(); - rcViewDockWidget->hide(); - headUpDockWidget->hide(); - video1DockWidget->hide(); - video2DockWidget->hide(); - break; - case VIEW_OPERATOR: - centerStack->setCurrentWidget(mapWidget); - controlDockWidget->hide(); - listDockWidget->show(); - waypointsDockWidget->show(); - infoDockWidget->hide(); - debugConsoleDockWidget->show(); - logPlayerDockWidget->show(); - parametersDockWidget->hide(); - hsiDockWidget->show(); - headDown1DockWidget->hide(); - headDown2DockWidget->hide(); - rcViewDockWidget->hide(); - headUpDockWidget->show(); - video1DockWidget->hide(); - video2DockWidget->hide(); - mavlinkInspectorWidget->hide(); - break; - case VIEW_UNCONNECTED: - case VIEW_FULL: - default: - centerStack->setCurrentWidget(mapWidget); - controlDockWidget->hide(); - listDockWidget->show(); - waypointsDockWidget->hide(); - infoDockWidget->hide(); - debugConsoleDockWidget->show(); - logPlayerDockWidget->show(); - parametersDockWidget->hide(); - hsiDockWidget->hide(); - headDown1DockWidget->hide(); - headDown2DockWidget->hide(); - rcViewDockWidget->hide(); - headUpDockWidget->show(); - video1DockWidget->hide(); - video2DockWidget->hide(); - mavlinkInspectorWidget->show(); - break; - } - } - - // Restore the widget positions and size - if (settings.contains(getWindowStateKey())) - { - restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion()); - } -} - -void MainWindow::loadEngineerView() -{ - if (currentView != VIEW_ENGINEER) - { - storeViewState(); - currentView = VIEW_ENGINEER; - ui.actionEngineersView->setChecked(true); - loadViewState(); - } -} - -void MainWindow::loadOperatorView() -{ - if (currentView != VIEW_OPERATOR) - { - storeViewState(); - currentView = VIEW_OPERATOR; - ui.actionOperatorsView->setChecked(true); - loadViewState(); - } -} - -void MainWindow::loadUnconnectedView() -{ - if (currentView != VIEW_UNCONNECTED) - { - storeViewState(); - currentView = VIEW_UNCONNECTED; - ui.actionUnconnectedView->setChecked(true); - loadViewState(); - } -} - -void MainWindow::loadPilotView() -{ - if (currentView != VIEW_PILOT) - { - storeViewState(); - currentView = VIEW_PILOT; - ui.actionPilotsView->setChecked(true); - loadViewState(); - } -} - -void MainWindow::loadMAVLinkView() -{ - if (currentView != VIEW_MAVLINK) - { - storeViewState(); - currentView = VIEW_MAVLINK; - ui.actionMavlinkView->setChecked(true); - loadViewState(); - } -} - -void MainWindow::loadFirmwareUpdateView() -{ - if (currentView != VIEW_FIRMWAREUPDATE) - { - storeViewState(); - currentView = VIEW_FIRMWAREUPDATE; - ui.actionFirmwareUpdateView->setChecked(true); - loadViewState(); - } -} - -void MainWindow::loadDataView(QString fileName) -{ - // Plot is now selected, now load data from file - if (dataplotWidget) - { - dataplotWidget->loadFile(fileName); - } - QStackedWidget *centerStack = dynamic_cast(centralWidget()); - if (centerStack) - { - centerStack->setCurrentWidget(dataplotWidget); - dataplotWidget->loadFile(fileName); - } -} - - -QList MainWindow::listLinkMenuActions(void) -{ - return ui.menuNetwork->actions(); -} +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009 - 2011 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +/** + * @file + * @brief Implementation of class MainWindow + * @author Lorenz Meier + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "QGC.h" +#include "MAVLinkSimulationLink.h" +#include "SerialLink.h" +#include "UDPLink.h" +#include "MAVLinkProtocol.h" +#include "CommConfigurationWindow.h" +#include "QGCWaypointListMulti.h" +#include "MainWindow.h" +#include "JoystickWidget.h" +#include "GAudioOutput.h" +#include "QGCToolWidget.h" +#include "QGCMAVLinkLogPlayer.h" +#include "QGCSettingsWidget.h" +#include "QGCMapTool.h" +#include "MAVLinkDecoder.h" +#include "QGCMAVLinkMessageSender.h" +#include "QGCRGBDView.h" +#include "QGCFirmwareUpdate.h" + +#ifdef QGC_OSG_ENABLED +#include "Q3DWidgetFactory.h" +#endif + +// FIXME Move +#include "PxQuadMAV.h" +#include "SlugsMAV.h" + + +#include "LogCompressor.h" + +MainWindow* MainWindow::instance(QSplashScreen* screen) +{ + static MainWindow* _instance = 0; + if(_instance == 0) + { + _instance = new MainWindow(); + if (screen) connect(_instance, SIGNAL(initStatusChanged(QString)), screen, SLOT(showMessage(QString))); + + /* Set the application as parent to ensure that this object + * will be destroyed when the main application exits */ + //_instance->setParent(qApp); + } + return _instance; +} + +/** +* Create new mainwindow. The constructor instantiates all parts of the user +* interface. It does NOT show the mainwindow. To display it, call the show() +* method. +* +* @see QMainWindow::show() +**/ +MainWindow::MainWindow(QWidget *parent): + QMainWindow(parent), + currentView(VIEW_UNCONNECTED), + currentStyle(QGC_MAINWINDOW_STYLE_INDOOR), + aboutToCloseFlag(false), + changingViewsFlag(false), + centerStackActionGroup(new QActionGroup(this)), + styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"), + autoReconnect(false), + lowPowerMode(false) +{ + hide(); + emit initStatusChanged("Loading UI Settings.."); + loadSettings(); + if (!settings.contains("CURRENT_VIEW")) + { + // Set this view as default view + settings.setValue("CURRENT_VIEW", currentView); + } + else + { + // LOAD THE LAST VIEW + VIEW_SECTIONS currentViewCandidate = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", currentView).toInt(); + if (currentViewCandidate != VIEW_ENGINEER && + currentViewCandidate != VIEW_OPERATOR && + currentViewCandidate != VIEW_PILOT && + currentViewCandidate != VIEW_FULL) + { + currentView = currentViewCandidate; + } + } + + settings.sync(); + + emit initStatusChanged("Loading Style."); + loadStyle(currentStyle); + + emit initStatusChanged("Setting up user interface."); + + // Setup user interface + ui.setupUi(this); + hide(); + + // Set dock options + setDockOptions(AnimatedDocks | AllowTabbedDocks | AllowNestedDocks); + statusBar()->setSizeGripEnabled(true); + + configureWindowName(); + + // Setup corners + setCorner(Qt::BottomRightCorner, Qt::RightDockWidgetArea); + + // Setup UI state machines + centerStackActionGroup->setExclusive(true); + + centerStack = new QStackedWidget(this); + setCentralWidget(centerStack); + + // Load Toolbar + toolBar = new QGCToolBar(this); + this->addToolBar(toolBar); + // Add actions + toolBar->addPerspectiveChangeAction(ui.actionOperatorsView); + toolBar->addPerspectiveChangeAction(ui.actionEngineersView); + toolBar->addPerspectiveChangeAction(ui.actionPilotsView); + + emit initStatusChanged("Building common widgets."); + + buildCommonWidgets(); + connectCommonWidgets(); + + emit initStatusChanged("Building common actions."); + + // Create actions + connectCommonActions(); + + // Populate link menu + emit initStatusChanged("Populating link menu"); + QList links = LinkManager::instance()->getLinks(); + foreach(LinkInterface* link, links) + { + this->addLink(link); + } + + connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addLink(LinkInterface*))); + + // Connect user interface devices + emit initStatusChanged("Initializing joystick interface."); + joystickWidget = 0; + joystick = new JoystickInput(); + +#ifdef MOUSE_ENABLED_WIN + emit initStatusChanged("Initializing 3D mouse interface."); + + mouseInput = new Mouse3DInput(this); + mouse = new Mouse6dofInput(mouseInput); +#endif //MOUSE_ENABLED_WIN + +#if MOUSE_ENABLED_LINUX + emit initStatusChanged("Initializing 3D mouse interface."); + + mouse = new Mouse6dofInput(this); + connect(this, SIGNAL(x11EventOccured(XEvent*)), mouse, SLOT(handleX11Event(XEvent*))); +#endif //MOUSE_ENABLED_LINUX + + // Connect link + if (autoReconnect) + { + SerialLink* link = new SerialLink(); + // Add to registry + LinkManager::instance()->add(link); + LinkManager::instance()->addProtocol(link, mavlink); + link->connect(); + } + + // Set low power mode + enableLowPowerMode(lowPowerMode); + + // Initialize window state + windowStateVal = windowState(); + + emit initStatusChanged("Restoring last view state."); + + // Restore the window setup + loadViewState(); + + emit initStatusChanged("Restoring last window size."); + // Restore the window position and size + if (settings.contains(getWindowGeometryKey())) + { + // Restore the window geometry + restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray()); + show(); + } + else + { + // Adjust the size + const int screenWidth = QApplication::desktop()->width(); + const int screenHeight = QApplication::desktop()->height(); + + if (screenWidth < 1200) + { + showFullScreen(); + } + else + { + resize(screenWidth*0.67f, qMin(screenHeight, (int)(screenWidth*0.67f*0.67f))); + show(); + } + + } + + connect(&windowNameUpdateTimer, SIGNAL(timeout()), this, SLOT(configureWindowName())); + windowNameUpdateTimer.start(15000); + emit initStatusChanged("Done."); + show(); +} + +MainWindow::~MainWindow() +{ + if (mavlink) + { + delete mavlink; + mavlink = NULL; + } +// if (simulationLink) +// { +// simulationLink->deleteLater(); +// simulationLink = NULL; +// } + if (joystick) + { + delete joystick; + joystick = NULL; + } + + // Get and delete all dockwidgets and contained + // widgets + QObjectList childList(this->children()); + + QObjectList::iterator i; + QDockWidget* dockWidget; + for (i = childList.begin(); i != childList.end(); ++i) + { + dockWidget = dynamic_cast(*i); + if (dockWidget) + { + // Remove dock widget from main window + // removeDockWidget(dockWidget); + // delete dockWidget->widget(); + delete dockWidget; + dockWidget = NULL; + } + else if (dynamic_cast(*i)) + { + delete dynamic_cast(*i); + *i = NULL; + } + } + // Delete all UAS objects +} + +void MainWindow::resizeEvent(QResizeEvent * event) +{ + if (height() < 800) + { + ui.statusBar->setVisible(false); + } + else + { + ui.statusBar->setVisible(true); + ui.statusBar->setSizeGripEnabled(true); + } + + if (width() > 1200) + { + toolBar->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); + } + else + { + toolBar->setToolButtonStyle(Qt::ToolButtonIconOnly); + } + + QMainWindow::resizeEvent(event); +} + +QString MainWindow::getWindowStateKey() +{ + return QString::number(currentView)+"_windowstate"; +} + +QString MainWindow::getWindowGeometryKey() +{ + //return QString::number(currentView)+"_geometry"; + return "_geometry"; +} + +void MainWindow::buildCustomWidget() +{ + // Create custom widgets + QList widgets = QGCToolWidget::createWidgetsFromSettings(this); + + if (widgets.size() > 0) + { + ui.menuTools->addSeparator(); + } + + for(int i = 0; i < widgets.size(); ++i) + { + // Check if this widget already has a parent, do not create it in this case + QGCToolWidget* tool = widgets.at(i); + QDockWidget* dock = dynamic_cast(tool->parentWidget()); + if (!dock) + { + QDockWidget* dock = new QDockWidget(tool->windowTitle(), this); + dock->setObjectName(tool->objectName()+"_DOCK"); + dock->setWidget(tool); + connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); + QAction* showAction = new QAction(widgets.at(i)->windowTitle(), this); + showAction->setCheckable(true); + connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); + connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); + widgets.at(i)->setMainMenuAction(showAction); + ui.menuTools->addAction(showAction); + + // Load dock widget location (default is bottom) + Qt::DockWidgetArea location = static_cast (tool->getDockWidgetArea(currentView)); + + addDockWidget(location, dock); + } + } +} + +void MainWindow::buildCommonWidgets() +{ + //TODO: move protocol outside UI + mavlink = new MAVLinkProtocol(); + connect(mavlink, SIGNAL(protocolStatusMessage(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection); + // Add generic MAVLink decoder + mavlinkDecoder = new MAVLinkDecoder(mavlink, this); + + // Dock widgets + if (!controlDockWidget) + { + controlDockWidget = new QDockWidget(tr("Control"), this); + controlDockWidget->setObjectName("UNMANNED_SYSTEM_CONTROL_DOCKWIDGET"); + controlDockWidget->setWidget( new UASControlWidget(this) ); + addTool(controlDockWidget, tr("Control"), Qt::LeftDockWidgetArea); + } + + if (!listDockWidget) + { + listDockWidget = new QDockWidget(tr("Unmanned Systems"), this); + listDockWidget->setWidget( new UASListWidget(this) ); + listDockWidget->setObjectName("UNMANNED_SYSTEMS_LIST_DOCKWIDGET"); + addTool(listDockWidget, tr("Unmanned Systems"), Qt::RightDockWidgetArea); + } + + if (!waypointsDockWidget) + { + waypointsDockWidget = new QDockWidget(tr("Mission Plan"), this); + waypointsDockWidget->setWidget( new QGCWaypointListMulti(this) ); + waypointsDockWidget->setObjectName("WAYPOINT_LIST_DOCKWIDGET"); + addTool(waypointsDockWidget, tr("Mission Plan"), Qt::BottomDockWidgetArea); + } + + if (!infoDockWidget) + { + infoDockWidget = new QDockWidget(tr("Status Details"), this); + infoDockWidget->setWidget( new UASInfoWidget(this) ); + infoDockWidget->setObjectName("UAS_STATUS_DETAILS_DOCKWIDGET"); + addTool(infoDockWidget, tr("Status Details"), Qt::RightDockWidgetArea); + } + + if (!debugConsoleDockWidget) + { + debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this); + debugConsoleDockWidget->setWidget( new DebugConsole(this) ); + debugConsoleDockWidget->setObjectName("COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET"); + + DebugConsole *debugConsole = dynamic_cast(debugConsoleDockWidget->widget()); + connect(mavlinkDecoder, SIGNAL(textMessageReceived(int, int, int, const QString)), debugConsole, SLOT(receiveTextMessage(int, int, int, const QString))); + + addTool(debugConsoleDockWidget, tr("Communication Console"), Qt::BottomDockWidgetArea); + } + + if (!logPlayerDockWidget) + { + logPlayerDockWidget = new QDockWidget(tr("MAVLink Log Player"), this); + logPlayer = new QGCMAVLinkLogPlayer(mavlink, this); + toolBar->setLogPlayer(logPlayer); + logPlayerDockWidget->setWidget(logPlayer); + logPlayerDockWidget->setObjectName("MAVLINK_LOG_PLAYER_DOCKWIDGET"); + addTool(logPlayerDockWidget, tr("MAVLink Log Replay"), Qt::RightDockWidgetArea); + } + + if (!mavlinkInspectorWidget) + { + mavlinkInspectorWidget = new QDockWidget(tr("MAVLink Message Inspector"), this); + mavlinkInspectorWidget->setWidget( new QGCMAVLinkInspector(mavlink, this) ); + mavlinkInspectorWidget->setObjectName("MAVLINK_INSPECTOR_DOCKWIDGET"); + addTool(mavlinkInspectorWidget, tr("MAVLink Inspector"), Qt::RightDockWidgetArea); + } + + if (!mavlinkSenderWidget) + { +// mavlinkSenderWidget = new QDockWidget(tr("MAVLink Message Sender"), this); +// mavlinkSenderWidget->setWidget( new QGCMAVLinkMessageSender(mavlink, this) ); +// mavlinkSenderWidget->setObjectName("MAVLINK_SENDER_DOCKWIDGET"); +// addTool(mavlinkSenderWidget, tr("MAVLink Sender"), Qt::RightDockWidgetArea); + } + + //FIXME: memory of acceptList will never be freed again + QStringList* acceptList = new QStringList(); + acceptList->append("-3.3,ATTITUDE.roll,rad,+3.3,s"); + acceptList->append("-3.3,ATTITUDE.pitch,deg,+3.3,s"); + acceptList->append("-3.3,ATTITUDE.yaw,deg,+3.3,s"); + + //FIXME: memory of acceptList2 will never be freed again + QStringList* acceptList2 = new QStringList(); + acceptList2->append("0,RAW_PRESSURE.pres_abs,hPa,65500"); + + if (!parametersDockWidget) + { + parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this); + parametersDockWidget->setWidget( new ParameterInterface(this) ); + parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET"); + addTool(parametersDockWidget, tr("Onboard Parameters"), Qt::RightDockWidgetArea); + } + + if (!hsiDockWidget) + { + hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this); + hsiDockWidget->setWidget( new HSIDisplay(this) ); + hsiDockWidget->setObjectName("HORIZONTAL_SITUATION_INDICATOR_DOCK_WIDGET"); + addTool(hsiDockWidget, tr("Horizontal Situation"), Qt::BottomDockWidgetArea); + } + + if (!headDown1DockWidget) + { + headDown1DockWidget = new QDockWidget(tr("Flight Display"), this); + HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this); + hdDisplay->addSource(mavlinkDecoder); + headDown1DockWidget->setWidget(hdDisplay); + headDown1DockWidget->setObjectName("HEAD_DOWN_DISPLAY_1_DOCK_WIDGET"); + addTool(headDown1DockWidget, tr("Flight Display"), Qt::RightDockWidgetArea); + } + + if (!headDown2DockWidget) + { + headDown2DockWidget = new QDockWidget(tr("Actuator Status"), this); + HDDisplay* hdDisplay = new HDDisplay(acceptList2, "Actuator Status", this); + hdDisplay->addSource(mavlinkDecoder); + headDown2DockWidget->setWidget(hdDisplay); + headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET"); + addTool(headDown2DockWidget, tr("Actuator Status"), Qt::RightDockWidgetArea); + } + + if (!rcViewDockWidget) + { + rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); + rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); + rcViewDockWidget->setObjectName("RADIO_CONTROL_CHANNELS_DOCK_WIDGET"); + addTool(rcViewDockWidget, tr("Radio Control"), Qt::BottomDockWidgetArea); + } + + if (!headUpDockWidget) + { + headUpDockWidget = new QDockWidget(tr("HUD"), this); + headUpDockWidget->setWidget( new HUD(320, 240, this)); + headUpDockWidget->setObjectName("HEAD_UP_DISPLAY_DOCK_WIDGET"); + addTool(headUpDockWidget, tr("Head Up Display"), Qt::RightDockWidgetArea); + } + + if (!video1DockWidget) + { + video1DockWidget = new QDockWidget(tr("Video Stream 1"), this); + QGCRGBDView* video1 = new QGCRGBDView(160, 120, this); + video1->enableHUDInstruments(false); + video1->enableVideo(false); + // FIXME select video stream as well + video1DockWidget->setWidget(video1); + video1DockWidget->setObjectName("VIDEO_STREAM_1_DOCK_WIDGET"); + addTool(video1DockWidget, tr("Video Stream 1"), Qt::LeftDockWidgetArea); + } + + if (!video2DockWidget) + { + video2DockWidget = new QDockWidget(tr("Video Stream 2"), this); + QGCRGBDView* video2 = new QGCRGBDView(160, 120, this); + video2->enableHUDInstruments(false); + video2->enableVideo(false); + // FIXME select video stream as well + video2DockWidget->setWidget(video2); + video2DockWidget->setObjectName("VIDEO_STREAM_2_DOCK_WIDGET"); + addTool(video2DockWidget, tr("Video Stream 2"), Qt::LeftDockWidgetArea); + } + +// if (!rgbd1DockWidget) { +// rgbd1DockWidget = new QDockWidget(tr("Video Stream 1"), this); +// HUD* video1 = new HUD(160, 120, this); +// video1->enableHUDInstruments(false); +// video1->enableVideo(true); +// // FIXME select video stream as well +// video1DockWidget->setWidget(video1); +// video1DockWidget->setObjectName("VIDEO_STREAM_1_DOCK_WIDGET"); +// addTool(video1DockWidget, tr("Video Stream 1"), Qt::LeftDockWidgetArea); +// } + +// if (!rgbd2DockWidget) { +// video2DockWidget = new QDockWidget(tr("Video Stream 2"), this); +// HUD* video2 = new HUD(160, 120, this); +// video2->enableHUDInstruments(false); +// video2->enableVideo(true); +// // FIXME select video stream as well +// video2DockWidget->setWidget(video2); +// video2DockWidget->setObjectName("VIDEO_STREAM_2_DOCK_WIDGET"); +// addTool(video2DockWidget, tr("Video Stream 2"), Qt::LeftDockWidgetArea); +// } + + // Custom widgets, added last to all menus and layouts + buildCustomWidget(); + + // Center widgets + if (!mapWidget) + { + mapWidget = new QGCMapTool(this); + addCentralWidget(mapWidget, "Maps"); + } + + if (!protocolWidget) + { + protocolWidget = new XMLCommProtocolWidget(this); + addCentralWidget(protocolWidget, "Mavlink Generator"); + } + +// if (!firmwareUpdateWidget) +// { +// firmwareUpdateWidget = new QGCFirmwareUpdate(this); +// addCentralWidget(firmwareUpdateWidget, "Firmware Update"); +// } + + if (!hudWidget) + { + hudWidget = new HUD(320, 240, this); + addCentralWidget(hudWidget, tr("Head Up Display")); + } + + if (!configWidget) + { + configWidget = new QGCVehicleConfig(this); + addCentralWidget(configWidget, tr("Vehicle Configuration")); + } + + if (!dataplotWidget) + { + dataplotWidget = new QGCDataPlot2D(this); + addCentralWidget(dataplotWidget, tr("Logfile Plot")); + } + +#ifdef QGC_OSG_ENABLED + if (!_3DWidget) + { + _3DWidget = Q3DWidgetFactory::get("PIXHAWK", this); + addCentralWidget(_3DWidget, tr("Local 3D")); + } +#endif + +#if (defined _MSC_VER) | (defined Q_OS_MAC) + if (!gEarthWidget) + { + gEarthWidget = new QGCGoogleEarthView(this); + addCentralWidget(gEarthWidget, tr("Google Earth")); + } +#endif +} + +void MainWindow::addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea area) +{ + QAction* tempAction = ui.menuTools->addAction(title); + + tempAction->setCheckable(true); + QVariant var; + var.setValue((QWidget*)widget); + tempAction->setData(var); + connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); + connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool))); + tempAction->setChecked(widget->isVisible()); + addDockWidget(area, widget); +} + + +void MainWindow::showTool(bool show) +{ + QAction* act = qobject_cast(sender()); + QWidget* widget = qVariantValue(act->data()); + widget->setVisible(show); +} + +void MainWindow::addCentralWidget(QWidget* widget, const QString& title) +{ + // Check if this widget already has been added + if (centerStack->indexOf(widget) == -1) + { + centerStack->addWidget(widget); + + QAction* tempAction = ui.menuMain->addAction(title); + + tempAction->setCheckable(true); + QVariant var; + var.setValue((QWidget*)widget); + tempAction->setData(var); + centerStackActionGroup->addAction(tempAction); + connect(tempAction,SIGNAL(triggered()),this, SLOT(showCentralWidget())); + connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool))); + tempAction->setChecked(widget->isVisible()); + } +} + + +void MainWindow::showCentralWidget() +{ + QAction* act = qobject_cast(sender()); + QWidget* widget = qVariantValue(act->data()); + centerStack->setCurrentWidget(widget); +} + +void MainWindow::showHILConfigurationWidget(UASInterface* uas) +{ + // Add simulation configuration widget + UAS* mav = dynamic_cast(uas); + + if (mav) + { + QGCHilConfiguration* hconf = new QGCHilConfiguration(mav, this); + QString hilDockName = tr("HIL Config (%1)").arg(uas->getUASName()); + QDockWidget* hilDock = new QDockWidget(hilDockName, this); + hilDock->setWidget(hconf); + hilDock->setObjectName(QString("HIL_CONFIG_%1").arg(uas->getUASID())); + addTool(hilDock, hilDockName, Qt::RightDockWidgetArea); + + } + + // Reload view state in case new widgets were added + loadViewState(); +} + +void MainWindow::closeEvent(QCloseEvent *event) +{ + if (isVisible()) storeViewState(); + storeSettings(); + aboutToCloseFlag = true; + mavlink->storeSettings(); + UASManager::instance()->storeSettings(); + QMainWindow::closeEvent(event); +} + +/** + * Connect the signals and slots of the common window widgets + */ +void MainWindow::connectCommonWidgets() +{ + if (infoDockWidget && infoDockWidget->widget()) + { + connect(mavlink, SIGNAL(receiveLossChanged(int, float)), + infoDockWidget->widget(), SLOT(updateSendLoss(int, float))); + } +} + +void MainWindow::createCustomWidget() +{ + QDockWidget* dock = new QDockWidget("Unnamed Tool", this); + QGCToolWidget* tool = new QGCToolWidget("Unnamed Tool", dock); + + if (QGCToolWidget::instances()->size() < 2) + { + // This is the first widget + ui.menuTools->addSeparator(); + } + + connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); + dock->setWidget(tool); + + QAction* showAction = new QAction(tool->getTitle(), this); + showAction->setCheckable(true); + connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); + connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); + tool->setMainMenuAction(showAction); + ui.menuTools->addAction(showAction); + this->addDockWidget(Qt::BottomDockWidgetArea, dock); + dock->setVisible(true); +} + +void MainWindow::loadCustomWidget() +{ + QString widgetFileExtension(".qgw"); + QString fileName = QFileDialog::getOpenFileName(this, tr("Specify Widget File Name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("QGroundControl Widget (*%1);;").arg(widgetFileExtension)); + if (fileName != "") loadCustomWidget(fileName); +} + +void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) +{ + QGCToolWidget* tool = new QGCToolWidget("", this); + if (tool->loadSettings(fileName, true) || !singleinstance) + { + // Add widget to UI + QDockWidget* dock = new QDockWidget(tool->getTitle(), this); + connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater())); + dock->setWidget(tool); + tool->setParent(dock); + + QAction* showAction = new QAction(tool->getTitle(), this); + showAction->setCheckable(true); + connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool))); + connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool))); + tool->setMainMenuAction(showAction); + ui.menuTools->addAction(showAction); + this->addDockWidget(Qt::BottomDockWidgetArea, dock); + dock->setVisible(true); + } + else + { + return; + } +} + +void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType) +{ + QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/widgets/"; + QString platformDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; + + QDir widgets(defaultsDir); + QStringList files = widgets.entryList(); + QDir platformWidgets(platformDir); + files.append(platformWidgets.entryList()); + + if (files.count() == 0) + { + qDebug() << "No default custom widgets for system " << systemType << "autopilot" << autopilotType << " found"; + qDebug() << "Tried with path: " << defaultsDir; + showStatusMessage(tr("Did not find any custom widgets in %1").arg(defaultsDir)); + } + + // Load all custom widgets found in the AP folder + for(int i = 0; i < files.count(); ++i) + { + QString file = files[i]; + if (file.endsWith(".qgw")) + { + // Will only be loaded if not already a custom widget with + // the same name is present + loadCustomWidget(defaultsDir+"/"+file, true); + showStatusMessage(tr("Loaded custom widget %1").arg(defaultsDir+"/"+file)); + } + } +} + +void MainWindow::loadSettings() +{ + QSettings settings; + settings.beginGroup("QGC_MAINWINDOW"); + autoReconnect = settings.value("AUTO_RECONNECT", autoReconnect).toBool(); + currentStyle = (QGC_MAINWINDOW_STYLE)settings.value("CURRENT_STYLE", currentStyle).toInt(); + lowPowerMode = settings.value("LOW_POWER_MODE", lowPowerMode).toBool(); + settings.endGroup(); +} + +void MainWindow::storeSettings() +{ + QSettings settings; + settings.beginGroup("QGC_MAINWINDOW"); + settings.setValue("AUTO_RECONNECT", autoReconnect); + settings.setValue("CURRENT_STYLE", currentStyle); + settings.endGroup(); + if (!aboutToCloseFlag && isVisible()) + { + settings.setValue(getWindowGeometryKey(), saveGeometry()); + // Save the last current view in any case + settings.setValue("CURRENT_VIEW", currentView); + // Save the current window state, but only if a system is connected (else no real number of widgets would be present) + if (UASManager::instance()->getUASList().length() > 0) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); + // Save the current view only if a UAS is connected + if (UASManager::instance()->getUASList().length() > 0) settings.setValue("CURRENT_VIEW_WITH_UAS_CONNECTED", currentView); + // Save the current power mode + } + settings.setValue("LOW_POWER_MODE", lowPowerMode); + settings.sync(); +} + +void MainWindow::configureWindowName() +{ + QList hostAddresses = QNetworkInterface::allAddresses(); + QString windowname = qApp->applicationName() + " " + qApp->applicationVersion(); + bool prevAddr = false; + + windowname.append(" (" + QHostInfo::localHostName() + ": "); + + for (int i = 0; i < hostAddresses.size(); i++) + { + // Exclude loopback IPv4 and all IPv6 addresses + if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":")) + { + if(prevAddr) windowname.append("/"); + windowname.append(hostAddresses.at(i).toString()); + prevAddr = true; + } + } + + windowname.append(")"); + + setWindowTitle(windowname); + +#ifndef Q_WS_MAC + //qApp->setWindowIcon(QIcon(":/core/images/qtcreator_logo_128.png")); +#endif +} + +void MainWindow::startVideoCapture() +{ + QString format = "bmp"; + QString initialPath = QDir::currentPath() + tr("/untitled.") + format; + + QString screenFileName = QFileDialog::getSaveFileName(this, tr("Save As"), + initialPath, + tr("%1 Files (*.%2);;All Files (*)") + .arg(format.toUpper()) + .arg(format)); + delete videoTimer; + videoTimer = new QTimer(this); + //videoTimer->setInterval(40); + //connect(videoTimer, SIGNAL(timeout()), this, SLOT(saveScreen())); + //videoTimer->stop(); +} + +void MainWindow::stopVideoCapture() +{ + videoTimer->stop(); + + // TODO Convert raw images to PNG +} + +void MainWindow::saveScreen() +{ + QPixmap window = QPixmap::grabWindow(this->winId()); + QString format = "bmp"; + + if (!screenFileName.isEmpty()) + { + window.save(screenFileName, format.toAscii()); + } +} + +void MainWindow::enableAutoReconnect(bool enabled) +{ + autoReconnect = enabled; +} + +void MainWindow::loadNativeStyle() +{ + loadStyle(QGC_MAINWINDOW_STYLE_NATIVE); +} + +void MainWindow::loadIndoorStyle() +{ + loadStyle(QGC_MAINWINDOW_STYLE_INDOOR); +} + +void MainWindow::loadOutdoorStyle() +{ + loadStyle(QGC_MAINWINDOW_STYLE_OUTDOOR); +} + +void MainWindow::loadStyle(QGC_MAINWINDOW_STYLE style) +{ + switch (style) { + case QGC_MAINWINDOW_STYLE_NATIVE: { + // Native mode means setting no style + // so if we were already in native mode + // take no action + // Only if a style was set, remove it. + if (style != currentStyle) { + qApp->setStyleSheet(""); + showInfoMessage(tr("Please restart QGroundControl"), tr("Please restart QGroundControl to switch to fully native look and feel. Currently you have loaded Qt's plastique style.")); + } + } + break; + case QGC_MAINWINDOW_STYLE_INDOOR: + qApp->setStyle("plastique"); + styleFileName = ":files/styles/style-indoor.css"; + reloadStylesheet(); + break; + case QGC_MAINWINDOW_STYLE_OUTDOOR: + qApp->setStyle("plastique"); + styleFileName = ":files/styles/style-outdoor.css"; + reloadStylesheet(); + break; + } + currentStyle = style; +} + +void MainWindow::selectStylesheet() +{ + // Let user select style sheet + styleFileName = QFileDialog::getOpenFileName(this, tr("Specify stylesheet"), styleFileName, tr("CSS Stylesheet (*.css);;")); + + if (!styleFileName.endsWith(".css")) + { + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Information); + msgBox.setText(tr("QGroundControl did lot load a new style")); + msgBox.setInformativeText(tr("No suitable .css file selected. Please select a valid .css file.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + return; + } + + // Load style sheet + reloadStylesheet(); +} + +void MainWindow::reloadStylesheet() +{ + // Load style sheet + QFile* styleSheet = new QFile(styleFileName); + if (!styleSheet->exists()) + { + styleSheet = new QFile(":files/styles/style-indoor.css"); + } + if (styleSheet->open(QIODevice::ReadOnly | QIODevice::Text)) + { + QString style = QString(styleSheet->readAll()); + style.replace("ICONDIR", QCoreApplication::applicationDirPath()+ "files/styles/"); + qApp->setStyleSheet(style); + } + else + { + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Information); + msgBox.setText(tr("QGroundControl did lot load a new style")); + msgBox.setInformativeText(tr("Stylesheet file %1 was not readable").arg(styleFileName)); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + } + delete styleSheet; +} + +/** + * The status message will be overwritten if a new message is posted to this function + * + * @param status message text + * @param timeout how long the status should be displayed + */ +void MainWindow::showStatusMessage(const QString& status, int timeout) +{ + statusBar()->showMessage(status, timeout); +} + +/** + * The status message will be overwritten if a new message is posted to this function. + * it will be automatically hidden after 5 seconds. + * + * @param status message text + */ +void MainWindow::showStatusMessage(const QString& status) +{ + statusBar()->showMessage(status, 20000); +} + +void MainWindow::showCriticalMessage(const QString& title, const QString& message) +{ + QMessageBox msgBox(this); + msgBox.setIcon(QMessageBox::Critical); + msgBox.setText(title); + msgBox.setInformativeText(message); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); +} + +void MainWindow::showInfoMessage(const QString& title, const QString& message) +{ + QMessageBox msgBox(this); + msgBox.setIcon(QMessageBox::Information); + msgBox.setText(title); + msgBox.setInformativeText(message); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); +} + +/** +* @brief Create all actions associated to the main window +* +**/ +void MainWindow::connectCommonActions() +{ + // Bind together the perspective actions + QActionGroup* perspectives = new QActionGroup(ui.menuPerspectives); + perspectives->addAction(ui.actionEngineersView); + perspectives->addAction(ui.actionMavlinkView); + perspectives->addAction(ui.actionPilotsView); + perspectives->addAction(ui.actionOperatorsView); + perspectives->addAction(ui.actionFirmwareUpdateView); + perspectives->addAction(ui.actionUnconnectedView); + perspectives->setExclusive(true); + + // Mark the right one as selected + if (currentView == VIEW_ENGINEER) ui.actionEngineersView->setChecked(true); + if (currentView == VIEW_MAVLINK) ui.actionMavlinkView->setChecked(true); + if (currentView == VIEW_PILOT) ui.actionPilotsView->setChecked(true); + if (currentView == VIEW_OPERATOR) ui.actionOperatorsView->setChecked(true); + if (currentView == VIEW_FIRMWAREUPDATE) ui.actionFirmwareUpdateView->setChecked(true); + if (currentView == VIEW_UNCONNECTED) ui.actionUnconnectedView->setChecked(true); + + // The UAS actions are not enabled without connection to system + ui.actionLiftoff->setEnabled(false); + ui.actionLand->setEnabled(false); + ui.actionEmergency_Kill->setEnabled(false); + ui.actionEmergency_Land->setEnabled(false); + ui.actionShutdownMAV->setEnabled(false); + + // Connect actions from ui + connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink())); + + // Connect internal actions + connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*))); + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); + + // Unmanned System controls + connect(ui.actionLiftoff, SIGNAL(triggered()), UASManager::instance(), SLOT(launchActiveUAS())); + connect(ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS())); + connect(ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS())); + connect(ui.actionEmergency_Kill, SIGNAL(triggered()), UASManager::instance(), SLOT(killActiveUAS())); + connect(ui.actionShutdownMAV, SIGNAL(triggered()), UASManager::instance(), SLOT(shutdownActiveUAS())); + connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS())); + + // Views actions + connect(ui.actionPilotsView, SIGNAL(triggered()), this, SLOT(loadPilotView())); + connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView())); + connect(ui.actionOperatorsView, SIGNAL(triggered()), this, SLOT(loadOperatorView())); + connect(ui.actionUnconnectedView, SIGNAL(triggered()), this, SLOT(loadUnconnectedView())); + + connect(ui.actionFirmwareUpdateView, SIGNAL(triggered()), this, SLOT(loadFirmwareUpdateView())); + connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView())); + + connect(ui.actionReloadStylesheet, SIGNAL(triggered()), this, SLOT(reloadStylesheet())); + connect(ui.actionSelectStylesheet, SIGNAL(triggered()), this, SLOT(selectStylesheet())); + + // Help Actions + connect(ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp())); + connect(ui.actionDeveloper_Credits, SIGNAL(triggered()), this, SLOT(showCredits())); + connect(ui.actionProject_Roadmap_2, SIGNAL(triggered()), this, SLOT(showRoadMap())); + + // Custom widget actions + connect(ui.actionNewCustomWidget, SIGNAL(triggered()), this, SLOT(createCustomWidget())); + connect(ui.actionLoadCustomWidgetFile, SIGNAL(triggered()), this, SLOT(loadCustomWidget())); + + // Audio output + ui.actionMuteAudioOutput->setChecked(GAudioOutput::instance()->isMuted()); + connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), ui.actionMuteAudioOutput, SLOT(setChecked(bool))); + connect(ui.actionMuteAudioOutput, SIGNAL(triggered(bool)), GAudioOutput::instance(), SLOT(mute(bool))); + + // User interaction + // NOTE: Joystick thread is not started and + // configuration widget is not instantiated + // unless it is actually used + // so no ressources spend on this. + ui.actionJoystickSettings->setVisible(true); + + // Configuration + // Joystick + connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure())); + // Application Settings + connect(ui.actionSettings, SIGNAL(triggered()), this, SLOT(showSettings())); +} + +void MainWindow::showHelp() +{ + if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/users/start"))) + { + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Critical); + msgBox.setText("Could not open help in browser"); + msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/user_guide in a browser."); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + } +} + +void MainWindow::showCredits() +{ + if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/credits"))) + { + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Critical); + msgBox.setText("Could not open credits in browser"); + msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/credits in a browser."); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + } +} + +void MainWindow::showRoadMap() +{ + if(!QDesktopServices::openUrl(QUrl("http://qgroundcontrol.org/dev/roadmap"))) + { + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Critical); + msgBox.setText("Could not open roadmap in browser"); + msgBox.setInformativeText("To get to the online help, please open http://qgroundcontrol.org/roadmap in a browser."); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + } +} + +void MainWindow::configure() +{ + if (!joystickWidget) + { + if (!joystick->isRunning()) + { + joystick->start(); + } + joystickWidget = new JoystickWidget(joystick); + } + joystickWidget->show(); +} + +void MainWindow::showSettings() +{ + QGCSettingsWidget* settings = new QGCSettingsWidget(this); + settings->show(); +} + +void MainWindow::addLink() +{ + SerialLink* link = new SerialLink(); + // TODO This should be only done in the dialog itself + + LinkManager::instance()->add(link); + LinkManager::instance()->addProtocol(link, mavlink); + + // Go fishing for this link's configuration window + QList actions = ui.menuNetwork->actions(); + + const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link)); + const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId()); + + foreach (QAction* act, actions) + { + if (act->data().toInt() == linkID) + { // LinkManager::instance()->getLinks().indexOf(link) + act->trigger(); + break; + } + } +} + +void MainWindow::addLink(LinkInterface *link) +{ + // IMPORTANT! KEEP THESE TWO LINES + // THEY MAKE SURE THE LINK IS PROPERLY REGISTERED + // BEFORE LINKING THE UI AGAINST IT + // Register (does nothing if already registered) + LinkManager::instance()->add(link); + LinkManager::instance()->addProtocol(link, mavlink); + + // Go fishing for this link's configuration window + QList actions = ui.menuNetwork->actions(); + + bool found(false); + + const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link)); + const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId()); + + foreach (QAction* act, actions) + { + if (act->data().toInt() == linkID) + { // LinkManager::instance()->getLinks().indexOf(link) + found = true; + } + } + + //UDPLink* udp = dynamic_cast(link); + + if (!found) + { // || udp + CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); + QAction* action = commWidget->getAction(); + ui.menuNetwork->addAction(action); + + // Error handling + connect(link, SIGNAL(communicationError(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection); + // Special case for simulationlink + MAVLinkSimulationLink* sim = dynamic_cast(link); + if (sim) + { + connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool))); + } + } +} + +void MainWindow::setActiveUAS(UASInterface* uas) +{ + // Enable and rename menu + ui.menuUnmanned_System->setTitle(uas->getUASName()); + if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true); +} + +void MainWindow::UASSpecsChanged(int uas) +{ + UASInterface* activeUAS = UASManager::instance()->getActiveUAS(); + if (activeUAS) + { + if (activeUAS->getUASID() == uas) + { + ui.menuUnmanned_System->setTitle(activeUAS->getUASName()); + } + } + else + { + // Last system deleted + ui.menuUnmanned_System->setTitle(tr("No System")); + ui.menuUnmanned_System->setEnabled(false); + } +} + +void MainWindow::UASCreated(UASInterface* uas) +{ + + // Connect the UAS to the full user interface + + //if (uas != NULL) + //{ + // The pilot, operator and engineer views were not available on startup, enable them now + ui.actionPilotsView->setEnabled(true); + ui.actionOperatorsView->setEnabled(true); + ui.actionEngineersView->setEnabled(true); + // The UAS actions are not enabled without connection to system + ui.actionLiftoff->setEnabled(true); + ui.actionLand->setEnabled(true); + ui.actionEmergency_Kill->setEnabled(true); + ui.actionEmergency_Land->setEnabled(true); + ui.actionShutdownMAV->setEnabled(true); + + QIcon icon; + // Set matching icon + switch (uas->getSystemType()) + { + case MAV_TYPE_GENERIC: + icon = QIcon(":files/images/mavs/generic.svg"); + break; + case MAV_TYPE_FIXED_WING: + icon = QIcon(":files/images/mavs/fixed-wing.svg"); + break; + case MAV_TYPE_QUADROTOR: + icon = QIcon(":files/images/mavs/quadrotor.svg"); + break; + case MAV_TYPE_COAXIAL: + icon = QIcon(":files/images/mavs/coaxial.svg"); + break; + case MAV_TYPE_HELICOPTER: + icon = QIcon(":files/images/mavs/helicopter.svg"); + break; + case MAV_TYPE_ANTENNA_TRACKER: + icon = QIcon(":files/images/mavs/antenna-tracker.svg"); + break; + case MAV_TYPE_GCS: + icon = QIcon(":files/images/mavs/groundstation.svg"); + break; + case MAV_TYPE_AIRSHIP: + icon = QIcon(":files/images/mavs/airship.svg"); + break; + case MAV_TYPE_FREE_BALLOON: + icon = QIcon(":files/images/mavs/free-balloon.svg"); + break; + case MAV_TYPE_ROCKET: + icon = QIcon(":files/images/mavs/rocket.svg"); + break; + case MAV_TYPE_GROUND_ROVER: + icon = QIcon(":files/images/mavs/ground-rover.svg"); + break; + case MAV_TYPE_SURFACE_BOAT: + icon = QIcon(":files/images/mavs/surface-boat.svg"); + break; + case MAV_TYPE_SUBMARINE: + icon = QIcon(":files/images/mavs/submarine.svg"); + break; + case MAV_TYPE_HEXAROTOR: + icon = QIcon(":files/images/mavs/hexarotor.svg"); + break; + case MAV_TYPE_OCTOROTOR: + icon = QIcon(":files/images/mavs/octorotor.svg"); + break; + case MAV_TYPE_TRICOPTER: + icon = QIcon(":files/images/mavs/tricopter.svg"); + break; + case MAV_TYPE_FLAPPING_WING: + icon = QIcon(":files/images/mavs/flapping-wing.svg"); + break; + case MAV_TYPE_KITE: + icon = QIcon(":files/images/mavs/kite.svg"); + break; + default: + icon = QIcon(":files/images/mavs/unknown.svg"); + break; + } + + QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems); + connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater())); + connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected())); + connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int))); + + ui.menuConnected_Systems->addAction(uasAction); + + // FIXME Should be not inside the mainwindow + if (debugConsoleDockWidget) + { + DebugConsole *debugConsole = dynamic_cast(debugConsoleDockWidget->widget()); + if (debugConsole) + { + connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), + debugConsole, SLOT(receiveTextMessage(int,int,int,QString))); + } + } + + // Health / System status indicator + if (infoDockWidget) + { + UASInfoWidget *infoWidget = dynamic_cast(infoDockWidget->widget()); + if (infoWidget) + { + infoWidget->addUAS(uas); + } + } + + // UAS List + if (listDockWidget) + { + UASListWidget *listWidget = dynamic_cast(listDockWidget->widget()); + if (listWidget) + { + listWidget->addUAS(uas); + } + } + + // Line chart + if (!linechartWidget) + { + // Center widgets + linechartWidget = new Linecharts(this); + linechartWidget->addSource(mavlinkDecoder); + addCentralWidget(linechartWidget, tr("Realtime Plot")); + } + + // Load default custom widgets for this autopilot type + loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName()); + + + if (uas->getAutopilotType() == MAV_AUTOPILOT_PIXHAWK) + { + // Dock widgets + if (!detectionDockWidget) + { + detectionDockWidget = new QDockWidget(tr("Object Recognition"), this); + detectionDockWidget->setWidget( new ObjectDetectionView("files/images/patterns", this) ); + detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET"); + addTool(detectionDockWidget, tr("Object Recognition"), Qt::RightDockWidgetArea); + } + + if (!watchdogControlDockWidget) + { + watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this); + watchdogControlDockWidget->setWidget( new WatchdogControl(this) ); + watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET"); + addTool(watchdogControlDockWidget, tr("Process Control"), Qt::BottomDockWidgetArea); + } + } + + // Change the view only if this is the first UAS + + // If this is the first connected UAS, it is both created as well as + // the currently active UAS + if (UASManager::instance()->getUASList().size() == 1) + { + // Load last view if setting is present + if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED")) + { + int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt(); + switch (view) + { + case VIEW_ENGINEER: + loadEngineerView(); + break; + case VIEW_MAVLINK: + loadMAVLinkView(); + break; + case VIEW_FIRMWAREUPDATE: + loadFirmwareUpdateView(); + break; + case VIEW_PILOT: + loadPilotView(); + break; + case VIEW_UNCONNECTED: + loadUnconnectedView(); + break; + case VIEW_OPERATOR: + default: + loadOperatorView(); + break; + } + } + else + { + loadOperatorView(); + } + } + + //} + + if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true); + if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true); + + // Reload view state in case new widgets were added + loadViewState(); +} + +void MainWindow::UASDeleted(UASInterface* uas) +{ + if (UASManager::instance()->getUASList().count() == 0) + { + // Last system deleted + ui.menuUnmanned_System->setTitle(tr("No System")); + ui.menuUnmanned_System->setEnabled(false); + } + + QAction* act; + QList actions = ui.menuConnected_Systems->actions(); + + foreach (act, actions) + { + if (act->text().contains(uas->getUASName())) + ui.menuConnected_Systems->removeAction(act); + } +} + +/** + * Stores the current view state + */ +void MainWindow::storeViewState() +{ + if (!aboutToCloseFlag) + { + // Save current state + settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); + settings.setValue(getWindowStateKey()+"CENTER_WIDGET", centerStack->currentIndex()); + // Although we want save the state of the window, we do not want to change the top-leve state (minimized, maximized, etc) + // therefore this state is stored here and restored after applying the rest of the settings in the new + // perspective. + windowStateVal = this->windowState(); + settings.setValue(getWindowGeometryKey(), saveGeometry()); + } +} + +void MainWindow::loadViewState() +{ + // Restore center stack state + int index = settings.value(getWindowStateKey()+"CENTER_WIDGET", -1).toInt(); + // The offline plot view is usually the consequence of a logging run, always show the realtime view first + if (centerStack->indexOf(dataplotWidget) == index) + { + // Rewrite to realtime plot + index = centerStack->indexOf(linechartWidget); + } + + if (index != -1) + { + centerStack->setCurrentIndex(index); + } + else + { + // Hide custom widgets + if (detectionDockWidget) detectionDockWidget->hide(); + if (watchdogControlDockWidget) watchdogControlDockWidget->hide(); + + // Load defaults + switch (currentView) + { + case VIEW_ENGINEER: + centerStack->setCurrentWidget(linechartWidget); + controlDockWidget->hide(); + listDockWidget->hide(); + waypointsDockWidget->hide(); + infoDockWidget->hide(); + debugConsoleDockWidget->show(); + logPlayerDockWidget->show(); + mavlinkInspectorWidget->show(); + //mavlinkSenderWidget->show(); + parametersDockWidget->show(); + hsiDockWidget->hide(); + headDown1DockWidget->hide(); + headDown2DockWidget->hide(); + rcViewDockWidget->hide(); + headUpDockWidget->hide(); + video1DockWidget->hide(); + video2DockWidget->hide(); + break; + case VIEW_PILOT: + centerStack->setCurrentWidget(hudWidget); + controlDockWidget->hide(); + listDockWidget->hide(); + waypointsDockWidget->hide(); + infoDockWidget->hide(); + debugConsoleDockWidget->hide(); + logPlayerDockWidget->hide(); + mavlinkInspectorWidget->hide(); + parametersDockWidget->hide(); + hsiDockWidget->show(); + headDown1DockWidget->show(); + headDown2DockWidget->show(); + rcViewDockWidget->hide(); + headUpDockWidget->hide(); + video1DockWidget->hide(); + video2DockWidget->hide(); + break; + case VIEW_MAVLINK: + centerStack->setCurrentWidget(protocolWidget); + controlDockWidget->hide(); + listDockWidget->hide(); + waypointsDockWidget->hide(); + infoDockWidget->hide(); + debugConsoleDockWidget->hide(); + logPlayerDockWidget->hide(); + mavlinkInspectorWidget->show(); + //mavlinkSenderWidget->show(); + parametersDockWidget->hide(); + hsiDockWidget->hide(); + headDown1DockWidget->hide(); + headDown2DockWidget->hide(); + rcViewDockWidget->hide(); + headUpDockWidget->hide(); + video1DockWidget->hide(); + video2DockWidget->hide(); + break; + case VIEW_FIRMWAREUPDATE: + centerStack->setCurrentWidget(firmwareUpdateWidget); + controlDockWidget->hide(); + listDockWidget->hide(); + waypointsDockWidget->hide(); + infoDockWidget->hide(); + debugConsoleDockWidget->hide(); + logPlayerDockWidget->hide(); + mavlinkInspectorWidget->hide(); + //mavlinkSenderWidget->hide(); + parametersDockWidget->hide(); + hsiDockWidget->hide(); + headDown1DockWidget->hide(); + headDown2DockWidget->hide(); + rcViewDockWidget->hide(); + headUpDockWidget->hide(); + video1DockWidget->hide(); + video2DockWidget->hide(); + break; + case VIEW_OPERATOR: + centerStack->setCurrentWidget(mapWidget); + controlDockWidget->hide(); + listDockWidget->show(); + waypointsDockWidget->show(); + infoDockWidget->hide(); + debugConsoleDockWidget->show(); + logPlayerDockWidget->show(); + parametersDockWidget->hide(); + hsiDockWidget->show(); + headDown1DockWidget->hide(); + headDown2DockWidget->hide(); + rcViewDockWidget->hide(); + headUpDockWidget->show(); + video1DockWidget->hide(); + video2DockWidget->hide(); + mavlinkInspectorWidget->hide(); + break; + case VIEW_UNCONNECTED: + case VIEW_FULL: + default: + centerStack->setCurrentWidget(mapWidget); + controlDockWidget->hide(); + listDockWidget->show(); + waypointsDockWidget->hide(); + infoDockWidget->hide(); + debugConsoleDockWidget->show(); + logPlayerDockWidget->show(); + parametersDockWidget->hide(); + hsiDockWidget->hide(); + headDown1DockWidget->hide(); + headDown2DockWidget->hide(); + rcViewDockWidget->hide(); + headUpDockWidget->show(); + video1DockWidget->hide(); + video2DockWidget->hide(); + mavlinkInspectorWidget->show(); + break; + } + } + + // Restore the widget positions and size + if (settings.contains(getWindowStateKey())) + { + restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion()); + } +} + +void MainWindow::loadEngineerView() +{ + if (currentView != VIEW_ENGINEER) + { + storeViewState(); + currentView = VIEW_ENGINEER; + ui.actionEngineersView->setChecked(true); + loadViewState(); + } +} + +void MainWindow::loadOperatorView() +{ + if (currentView != VIEW_OPERATOR) + { + storeViewState(); + currentView = VIEW_OPERATOR; + ui.actionOperatorsView->setChecked(true); + loadViewState(); + } +} + +void MainWindow::loadUnconnectedView() +{ + if (currentView != VIEW_UNCONNECTED) + { + storeViewState(); + currentView = VIEW_UNCONNECTED; + ui.actionUnconnectedView->setChecked(true); + loadViewState(); + } +} + +void MainWindow::loadPilotView() +{ + if (currentView != VIEW_PILOT) + { + storeViewState(); + currentView = VIEW_PILOT; + ui.actionPilotsView->setChecked(true); + loadViewState(); + } +} + +void MainWindow::loadMAVLinkView() +{ + if (currentView != VIEW_MAVLINK) + { + storeViewState(); + currentView = VIEW_MAVLINK; + ui.actionMavlinkView->setChecked(true); + loadViewState(); + } +} + +void MainWindow::loadFirmwareUpdateView() +{ + if (currentView != VIEW_FIRMWAREUPDATE) + { + storeViewState(); + currentView = VIEW_FIRMWAREUPDATE; + ui.actionFirmwareUpdateView->setChecked(true); + loadViewState(); + } +} + +void MainWindow::loadDataView(QString fileName) +{ + // Plot is now selected, now load data from file + if (dataplotWidget) + { + dataplotWidget->loadFile(fileName); + } + QStackedWidget *centerStack = dynamic_cast(centralWidget()); + if (centerStack) + { + centerStack->setCurrentWidget(dataplotWidget); + dataplotWidget->loadFile(fileName); + } +} + + +QList MainWindow::listLinkMenuActions(void) +{ + return ui.menuNetwork->actions(); +} + +#ifdef MOUSE_ENABLED_LINUX +bool MainWindow::x11Event(XEvent *event) +{ + emit x11EventOccured(event); + //qDebug("XEvent occured..."); + return false; +} +#endif // MOUSE_ENABLED_LINUX diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index b5d1f0a40aed8e02ca88545cf812c422d03c9ec1..8b71dbf8413c5c11d78255fbe614e47fa201099c 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -1,402 +1,421 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief Definition of class MainWindow - * @author Lorenz Meier - * - */ - -#ifndef _MAINWINDOW_H_ -#define _MAINWINDOW_H_ - -#include -#include -#include -#include -#include - -#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 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 linechartWidget; - QPointer hudWidget; - QPointer configWidget; - QPointer mapWidget; - QPointer protocolWidget; - QPointer dataplotWidget; -#ifdef QGC_OSG_ENABLED - QPointer _3DWidget; -#endif -#if (defined _MSC_VER) || (defined Q_OS_MAC) - QPointer gEarthWidget; -#endif - QPointer firmwareUpdateWidget; - - // Dock widgets - QPointer controlDockWidget; - QPointer controlParameterWidget; - QPointer infoDockWidget; - QPointer cameraDockWidget; - QPointer listDockWidget; - QPointer waypointsDockWidget; - QPointer detectionDockWidget; - QPointer debugConsoleDockWidget; - QPointer parametersDockWidget; - QPointer headDown1DockWidget; - QPointer headDown2DockWidget; - QPointer watchdogControlDockWidget; - - QPointer headUpDockWidget; - QPointer video1DockWidget; - QPointer video2DockWidget; - QPointer rgbd1DockWidget; - QPointer rgbd2DockWidget; - QPointer logPlayerDockWidget; - - QPointer hsiDockWidget; - QPointer rcViewDockWidget; - QPointer hudDockWidget; - QPointer slugsDataWidget; - QPointer slugsHilSimWidget; - QPointer slugsCamControlWidget; - - QPointer toolBar; - - QPointer mavlinkInspectorWidget; - QPointer mavlinkDecoder; - QPointer 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 + +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 . + +======================================================================*/ + +/** + * @file + * @brief Definition of class MainWindow + * @author Lorenz Meier + * + */ + +#ifndef _MAINWINDOW_H_ +#define _MAINWINDOW_H_ + +#include +#include +#include +#include +#include + +#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 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 linechartWidget; + QPointer hudWidget; + QPointer configWidget; + QPointer mapWidget; + QPointer protocolWidget; + QPointer dataplotWidget; +#ifdef QGC_OSG_ENABLED + QPointer _3DWidget; +#endif +#if (defined _MSC_VER) || (defined Q_OS_MAC) + QPointer gEarthWidget; +#endif + QPointer firmwareUpdateWidget; + + // Dock widgets + QPointer controlDockWidget; + QPointer controlParameterWidget; + QPointer infoDockWidget; + QPointer cameraDockWidget; + QPointer listDockWidget; + QPointer waypointsDockWidget; + QPointer detectionDockWidget; + QPointer debugConsoleDockWidget; + QPointer parametersDockWidget; + QPointer headDown1DockWidget; + QPointer headDown2DockWidget; + QPointer watchdogControlDockWidget; + + QPointer headUpDockWidget; + QPointer video1DockWidget; + QPointer video2DockWidget; + QPointer rgbd1DockWidget; + QPointer rgbd2DockWidget; + QPointer logPlayerDockWidget; + + QPointer hsiDockWidget; + QPointer rcViewDockWidget; + QPointer hudDockWidget; + QPointer slugsDataWidget; + QPointer slugsHilSimWidget; + QPointer slugsCamControlWidget; + + QPointer toolBar; + + QPointer mavlinkInspectorWidget; + QPointer mavlinkDecoder; + QPointer 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_ */ diff --git a/src/ui/PX4FirmwareUpgrader.cc b/src/ui/PX4FirmwareUpgrader.cc index 5d9fabff88dc60ec418b4263702e1b6851c43578..c2ae3fae80cee52f1bab56edc0ee55a8e5f99482 100644 --- a/src/ui/PX4FirmwareUpgrader.cc +++ b/src/ui/PX4FirmwareUpgrader.cc @@ -1,9 +1,14 @@ +#include +#include +#include + #include "PX4FirmwareUpgrader.h" #include "ui_PX4FirmwareUpgrader.h" #include #include + PX4FirmwareUpgrader::PX4FirmwareUpgrader(QWidget *parent) : QWidget(parent), ui(new Ui::PX4FirmwareUpgrader) @@ -21,7 +26,16 @@ PX4FirmwareUpgrader::~PX4FirmwareUpgrader() void PX4FirmwareUpgrader::selectFirmwareFile() { - + QSettings settings; + QString path = settings.value("PX4_FIRMWARE_PATH", + QDesktopServices::storageLocation(QDesktopServices::DesktopLocation)).toString(); + const QString widgetFileExtension(".px4"); + QString fileName = QFileDialog::getOpenFileName(this, tr("Specify File Name"), + path, + tr("PX4 Firmware (*%1);;").arg(widgetFileExtension)); + settings.setValue("PX4_FIRMWARE_PATH", fileName); + qDebug() << "EMITTING SIGNAL"; + emit firmwareFileNameSet(fileName); } void PX4FirmwareUpgrader::setDetectionStatusText(const QString &text) @@ -32,6 +46,7 @@ void PX4FirmwareUpgrader::setDetectionStatusText(const QString &text) void PX4FirmwareUpgrader::setFlashStatusText(const QString &text) { ui->flashProgressLabel->setText(text); + qDebug() << __FILE__ << __LINE__ << "LABEL" << text; } void PX4FirmwareUpgrader::setFlashProgress(int percent) diff --git a/src/ui/QGCHilConfiguration.cc b/src/ui/QGCHilConfiguration.cc index a83397ce172f2c2fd71edde401a633115861d9f7..d6253cefbc4f6f55da997e684b3bb2d4a9778b74 100644 --- a/src/ui/QGCHilConfiguration.cc +++ b/src/ui/QGCHilConfiguration.cc @@ -30,7 +30,12 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index) mav->enableHilFlightGear(false, ""); QGCHilFlightGearConfiguration* hfgconf = new QGCHilFlightGearConfiguration(mav, this); hfgconf->show(); - ui->simulatorConfigurationDockWidget->setWidget(hfgconf); + ui->simulatorConfigurationLayout->addWidget(hfgconf); + QGCFlightGearLink* fg = dynamic_cast(mav->getHILSimulation()); + if (fg) + { + connect(fg, SIGNAL(statusMessage(QString)), ui->statusLabel, SLOT(setText(QString))); + } } else if(2 == index || 3 == index) @@ -39,13 +44,14 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index) mav->enableHilXPlane(false); QGCHilXPlaneConfiguration* hxpconf = new QGCHilXPlaneConfiguration(mav->getHILSimulation(), this); hxpconf->show(); - ui->simulatorConfigurationDockWidget->setWidget(hxpconf); + ui->simulatorConfigurationLayout->addWidget(hxpconf); // Select correct version of XPlane QGCXPlaneLink* xplane = dynamic_cast(mav->getHILSimulation()); if (xplane) { xplane->setVersion((index == 2) ? 10 : 9); + connect(xplane, SIGNAL(statusMessage(QString)), ui->statusLabel, SLOT(setText(QString))); } } } diff --git a/src/ui/QGCHilConfiguration.ui b/src/ui/QGCHilConfiguration.ui index ace3110769acf16b2497c253695458ed782390c0..da8adaf2769fecdc06e15c4dcc803e2c33fa4a01 100644 --- a/src/ui/QGCHilConfiguration.ui +++ b/src/ui/QGCHilConfiguration.ui @@ -6,8 +6,8 @@ 0 0 - 305 - 355 + 366 + 301 @@ -19,22 +19,22 @@ Form - - - + + + - Simulator + Status - - + + - Status + Simulator - + true @@ -61,35 +61,12 @@ - - - - - 0 - 0 - - - - - 20 - 150 - - - - QDockWidget::NoDockWidgetFeatures + + + + 0 - - Simulator Options - - - - - 0 - 0 - - - - +
diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index 318ef8d756329efccc9165f47564ee2f618d5a73..e4e81c9d0a4a3e56225bb67ea9dce04eb372f465 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -11,6 +11,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : QWidget(parent), mav(NULL), + chanCount(0), changed(true), rc_mode(RC_MODE_2), rcRoll(0.0f), @@ -21,6 +22,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : rcAux1(0.0f), rcAux2(0.0f), rcAux3(0.0f), + calibrationEnabled(false), ui(new Ui::QGCVehicleConfig) { setObjectName("QGC_VEHICLECONFIG"); @@ -31,9 +33,31 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1); + ui->rcCalibrationButton->setCheckable(true); connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool))); connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters())); connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int))); + connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions())); + + /* Connect RC mapping assignments */ + connect(ui->rollSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setRollChan(int))); + connect(ui->pitchSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setPitchChan(int))); + connect(ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYawChan(int))); + connect(ui->throttleSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setThrottleChan(int))); + connect(ui->modeSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setModeChan(int))); + connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int))); + connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(int))); + connect(ui->aux3SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux3Chan(int))); + + // Connect RC reverse assignments + connect(ui->invertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setRollInverted(bool))); + connect(ui->invertCheckBox_2, SIGNAL(clicked(bool)), this, SLOT(setPitchInverted(bool))); + connect(ui->invertCheckBox_3, SIGNAL(clicked(bool)), this, SLOT(setYawInverted(bool))); + connect(ui->invertCheckBox_4, SIGNAL(clicked(bool)), this, SLOT(setThrottleInverted(bool))); + connect(ui->invertCheckBox_5, SIGNAL(clicked(bool)), this, SLOT(setModeInverted(bool))); + connect(ui->invertCheckBox_6, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool))); + connect(ui->invertCheckBox_7, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool))); + connect(ui->invertCheckBox_8, SIGNAL(clicked(bool)), this, SLOT(setAux3Inverted(bool))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); @@ -41,7 +65,8 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : for (unsigned int i = 0; i < chanMax; i++) { - rcValue[i] = 1500; + rcValue[i] = UINT16_MAX; + rcMapping[i] = i; } updateTimer.setInterval(150); @@ -75,15 +100,35 @@ void QGCVehicleConfig::toggleCalibrationRC(bool enabled) } } +void QGCVehicleConfig::setTrimPositions() +{ + // Set trim for roll, pitch, yaw, throttle + rcTrim[rcMapping[0]] = rcValue[rcMapping[0]]; // roll + rcTrim[rcMapping[1]] = rcValue[rcMapping[1]]; // pitch + rcTrim[rcMapping[2]] = rcValue[rcMapping[2]]; // yaw + rcTrim[rcMapping[3]] = rcMin[rcMapping[3]]; // throttle + rcTrim[rcMapping[4]] = ((rcMax[rcMapping[4]] - rcMin[rcMapping[4]]) / 2.0f) + rcMin[rcMapping[4]]; // mode sw + rcTrim[rcMapping[5]] = ((rcMax[rcMapping[5]] - rcMin[rcMapping[5]]) / 2.0f) + rcMin[rcMapping[5]]; // aux 1 + rcTrim[rcMapping[6]] = ((rcMax[rcMapping[6]] - rcMin[rcMapping[6]]) / 2.0f) + rcMin[rcMapping[6]]; // aux 2 + rcTrim[rcMapping[7]] = ((rcMax[rcMapping[7]] - rcMin[rcMapping[7]]) / 2.0f) + rcMin[rcMapping[7]]; // aux 3 +} + +void QGCVehicleConfig::detectChannelInversion() +{ + +} + void QGCVehicleConfig::startCalibrationRC() { ui->rcTypeComboBox->setEnabled(false); ui->rcCalibrationButton->setText(tr("Stop RC Calibration")); resetCalibrationRC(); + calibrationEnabled = true; } void QGCVehicleConfig::stopCalibrationRC() { + calibrationEnabled = false; ui->rcTypeComboBox->setEnabled(true); ui->rcCalibrationButton->setText(tr("Start RC Calibration")); } @@ -111,6 +156,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) // Reset current state resetCalibrationRC(); + chanCount = 0; + // Connect new system mav = active; connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this, @@ -130,13 +177,18 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) { toolWidgets.append(tool); ui->sensorLayout->addWidget(tool); + } else { + delete tool; } + // Load multirotor attitude pid tool = new QGCToolWidget("", this); if (tool->loadSettings(defaultsDir + "px4_mc_attitude_pid_params.qgw", false)) { toolWidgets.append(tool); ui->multiRotorAttitudeLayout->addWidget(tool); + } else { + delete tool; } // Load multirotor position pid @@ -145,6 +197,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) { toolWidgets.append(tool); ui->multiRotorPositionLayout->addWidget(tool); + } else { + delete tool; } // Load fixed wing attitude pid @@ -153,6 +207,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) { toolWidgets.append(tool); ui->fixedWingAttitudeLayout->addWidget(tool); + } else { + delete tool; } // Load fixed wing position pid @@ -161,6 +217,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) { toolWidgets.append(tool); ui->fixedWingPositionLayout->addWidget(tool); + } else { + delete tool; } updateStatus(QString("Reading from system %1").arg(mav->getUASName())); @@ -190,23 +248,36 @@ void QGCVehicleConfig::writeCalibrationRC() // Do not write the RC type, as these values depend on this // active onboard parameter - for (unsigned int i = 0; i < chanMax; ++i) + for (unsigned int i = 0; i < chanCount; ++i) { + //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i]; mav->setParameter(0, minTpl.arg(i+1), rcMin[i]); + QGC::SLEEP::usleep(50000); mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]); + QGC::SLEEP::usleep(50000); mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]); - mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1 : 1); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f); + QGC::SLEEP::usleep(50000); } // Write mappings - mav->setParameter(0, "RC_MAP_ROLL", rcMapping[0]); - mav->setParameter(0, "RC_MAP_PITCH", rcMapping[1]); - mav->setParameter(0, "RC_MAP_THROTTLE", rcMapping[2]); - mav->setParameter(0, "RC_MAP_YAW", rcMapping[3]); - mav->setParameter(0, "RC_MAP_MODE_SW", rcMapping[4]); - mav->setParameter(0, "RC_MAP_AUX1", rcMapping[5]); - mav->setParameter(0, "RC_MAP_AUX2", rcMapping[6]); - mav->setParameter(0, "RC_MAP_AUX3", rcMapping[7]); + mav->setParameter(0, "RC_MAP_ROLL", (int32_t)(rcMapping[0]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_PITCH", (int32_t)(rcMapping[1]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_MODE_SW", (int32_t)(rcMapping[4]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_AUX1", (int32_t)(rcMapping[5]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_AUX2", (int32_t)(rcMapping[6]+1)); + QGC::SLEEP::usleep(50000); + mav->setParameter(0, "RC_MAP_AUX3", (int32_t)(rcMapping[7]+1)); + QGC::SLEEP::usleep(50000); } void QGCVehicleConfig::requestCalibrationRC() @@ -238,126 +309,134 @@ void QGCVehicleConfig::writeParameters() { updateStatus(tr("Writing all onboard parameters.")); writeCalibrationRC(); + mav->writeParametersToStorage(); } void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) { -// /* scale around the mid point differently for lower and upper range */ -// if (ppm_buffer[i] > _rc.chan[i].mid + _parameters.dz[i]) { -// _rc.chan[i].scaled = ((ppm_buffer[i] - _parameters.trim[i]) / (_parameters.max[i] - _parameters.trim[i])); -// } else if ((ppm_buffer[i] < _rc_chan[i].mid - _parameters.dz[i])) { -// _rc.chan[i].scaled = -1.0 + ((ppm_buffer[i] - _parameters.min[i]) / (_parameters.trim[i] - _parameters.min[i])); -// } else { -// /* in the configured dead zone, output zero */ -// _rc.chan[i].scaled = 0.0f; -// } - - if (chan < 0 || static_cast(chan) >= chanMax) + // Check if index and values are sane + if (chan < 0 || static_cast(chan) >= chanMax || val < 500 || val > 2500) return; - if (val < rcMin[chan]) - { - rcMin[chan] = val; + if (chan + 1 > chanCount) { + chanCount = chan+1; + } + + // Update calibration data + if (calibrationEnabled) { + if (val < rcMin[chan]) + { + rcMin[chan] = val; + } + + if (val > rcMax[chan]) + { + rcMax[chan] = val; + } } - if (val > rcMax[chan]) + // Raw value + rcValue[chan] = val; + + // Normalized value + float normalized; + + if (val >= rcTrim[chan]) + { + normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); + } + else { - rcMax[chan] = val; + normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]); } + // Bound + normalized = qBound(-1.0f, normalized, 1.0f); + // Invert + normalized = (rcRev[chan]) ? -1.0f*normalized : normalized; + if (chan == rcMapping[0]) { // ROLL - if (rcRoll >= rcTrim[chan]) - { - rcRoll = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); - } - else - { - rcRoll = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]); - } - - rcValue[0] = val; - rcRoll = qBound(-1.0f, rcRoll, 1.0f); + rcRoll = normalized; } - else if (chan == rcMapping[1]) + if (chan == rcMapping[1]) { // PITCH - if (rcPitch >= rcTrim[chan]) - { - rcPitch = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); - } - else - { - rcPitch = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]); - } - rcValue[1] = val; - rcPitch = qBound(-1.0f, rcPitch, 1.0f); + rcPitch = normalized; } - else if (chan == rcMapping[2]) + if (chan == rcMapping[2]) { - // YAW - if (rcYaw >= rcTrim[chan]) - { - rcYaw = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); - } - else - { - rcYaw = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]); - } - rcValue[2] = val; - rcYaw = qBound(-1.0f, rcYaw, 1.0f); + rcYaw = normalized; } - else if (chan == rcMapping[3]) + if (chan == rcMapping[3]) { // THROTTLE - if (rcThrottle >= rcTrim[chan]) - { - rcThrottle = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); + if (rcRev[chan]) { + rcThrottle = 1.0f + normalized; + } else { + rcThrottle = normalized; } - else - { - rcThrottle = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]); - } - rcValue[3] = val; - rcThrottle = qBound(-1.0f, rcThrottle, 1.0f); + + rcThrottle = qBound(0.0f, rcThrottle, 1.0f); } - else if (chan == rcMapping[4]) + if (chan == rcMapping[4]) { // MODE SWITCH - if (rcMode >= rcTrim[chan]) - { - rcMode = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); - } - else - { - rcMode = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]); - } - rcValue[4] = val; - rcMode = qBound(-1.0f, rcMode, 1.0f); + rcMode = normalized; } - else if (chan == rcMapping[5]) + if (chan == rcMapping[5]) { // AUX1 - rcAux1 = val; - rcValue[5] = val; + rcAux1 = normalized; } - else if (chan == rcMapping[6]) + if (chan == rcMapping[6]) { // AUX2 - rcAux2 = val; - rcValue[6] = val; + rcAux2 = normalized; } - else if (chan == rcMapping[7]) + if (chan == rcMapping[7]) { // AUX3 - rcAux3 = val; - rcValue[7] = val; + rcAux3 = normalized; } changed = true; - //qDebug() << "RC CHAN:" << chan << "PPM:" << val; + //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized; +} + +void QGCVehicleConfig::updateInvertedCheckboxes(int index) +{ + unsigned int mapindex = rcMapping[index]; + + switch (mapindex) + { + case 0: + ui->invertCheckBox->setChecked(rcRev[index]); + break; + case 1: + ui->invertCheckBox_2->setChecked(rcRev[index]); + break; + case 2: + ui->invertCheckBox_3->setChecked(rcRev[index]); + break; + case 3: + ui->invertCheckBox_4->setChecked(rcRev[index]); + break; + case 4: + ui->invertCheckBox_5->setChecked(rcRev[index]); + break; + case 5: + ui->invertCheckBox_6->setChecked(rcRev[index]); + break; + case 6: + ui->invertCheckBox_7->setChecked(rcRev[index]); + break; + case 7: + ui->invertCheckBox_8->setChecked(rcRev[index]); + break; + } } void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) @@ -381,7 +460,8 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (minTpl.exactMatch(parameterName)) { bool ok; unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && (index > 0) && (index < chanMax)) + //qDebug() << "PARAM:" << parameterName << "index:" << index; + if (ok && (index >= 0) && (index < chanMax)) { rcMin[index] = value.toInt(); } @@ -390,7 +470,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (maxTpl.exactMatch(parameterName)) { bool ok; unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && (index > 0) && (index < chanMax)) + if (ok && (index >= 0) && (index < chanMax)) { rcMax[index] = value.toInt(); } @@ -399,7 +479,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (trimTpl.exactMatch(parameterName)) { bool ok; unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && (index > 0) && (index < chanMax)) + if (ok && (index >= 0) && (index < chanMax)) { rcTrim[index] = value.toInt(); } @@ -408,39 +488,10 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (revTpl.exactMatch(parameterName)) { bool ok; unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && (index > 0) && (index < chanMax)) + if (ok && (index >= 0) && (index < chanMax)) { rcRev[index] = (value.toInt() == -1) ? true : false; - - unsigned int mapindex = rcMapping[index]; - - switch (mapindex) - { - case 0: - ui->invertCheckBox->setChecked(rcRev[index]); - break; - case 1: - ui->invertCheckBox_2->setChecked(rcRev[index]); - break; - case 2: - ui->invertCheckBox_3->setChecked(rcRev[index]); - break; - case 3: - ui->invertCheckBox_4->setChecked(rcRev[index]); - break; - case 4: - ui->invertCheckBox_5->setChecked(rcRev[index]); - break; - case 5: - ui->invertCheckBox_6->setChecked(rcRev[index]); - break; - case 6: - ui->invertCheckBox_7->setChecked(rcRev[index]); - break; - case 7: - ui->invertCheckBox_8->setChecked(rcRev[index]); - break; - } + updateInvertedCheckboxes(index); } } @@ -461,77 +512,77 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3 if (parameterName.contains("RC_MAP_ROLL")) { - rcMapping[0] = value.toInt(); - ui->rollSpinBox->setValue(rcMapping[0]); + rcMapping[0] = value.toInt() - 1; + ui->rollSpinBox->setValue(rcMapping[0]+1); } if (parameterName.contains("RC_MAP_PITCH")) { - rcMapping[1] = value.toInt(); - ui->pitchSpinBox->setValue(rcMapping[1]); + rcMapping[1] = value.toInt() - 1; + ui->pitchSpinBox->setValue(rcMapping[1]+1); } if (parameterName.contains("RC_MAP_YAW")) { - rcMapping[2] = value.toInt(); - ui->yawSpinBox->setValue(rcMapping[2]); + rcMapping[2] = value.toInt() - 1; + ui->yawSpinBox->setValue(rcMapping[2]+1); } if (parameterName.contains("RC_MAP_THROTTLE")) { - rcMapping[3] = value.toInt(); - ui->throttleSpinBox->setValue(rcMapping[3]); + rcMapping[3] = value.toInt() - 1; + ui->throttleSpinBox->setValue(rcMapping[3]+1); } if (parameterName.contains("RC_MAP_MODE_SW")) { - rcMapping[4] = value.toInt(); - ui->modeSpinBox->setValue(rcMapping[4]); + rcMapping[4] = value.toInt() - 1; + ui->modeSpinBox->setValue(rcMapping[4]+1); } if (parameterName.contains("RC_MAP_AUX1")) { - rcMapping[5] = value.toInt(); - ui->aux1SpinBox->setValue(rcMapping[5]); + rcMapping[5] = value.toInt() - 1; + ui->aux1SpinBox->setValue(rcMapping[5]+1); } if (parameterName.contains("RC_MAP_AUX2")) { - rcMapping[6] = value.toInt(); - ui->aux1SpinBox->setValue(rcMapping[6]); + rcMapping[6] = value.toInt() - 1; + ui->aux1SpinBox->setValue(rcMapping[6]+1); } if (parameterName.contains("RC_MAP_AUX3")) { - rcMapping[7] = value.toInt(); - ui->aux1SpinBox->setValue(rcMapping[7]); + rcMapping[7] = value.toInt() - 1; + ui->aux1SpinBox->setValue(rcMapping[7]+1); } // Scaling if (parameterName.contains("RC_SCALE_ROLL")) { - rcScaling[0] = value.toInt(); + rcScaling[0] = value.toFloat(); } if (parameterName.contains("RC_SCALE_PITCH")) { - rcScaling[1] = value.toInt(); + rcScaling[1] = value.toFloat(); } if (parameterName.contains("RC_SCALE_YAW")) { - rcScaling[2] = value.toInt(); + rcScaling[2] = value.toFloat(); } if (parameterName.contains("RC_SCALE_THROTTLE")) { - rcScaling[3] = value.toInt(); + rcScaling[3] = value.toFloat(); } if (parameterName.contains("RC_SCALE_MODE_SW")) { - rcScaling[4] = value.toInt(); + rcScaling[4] = value.toFloat(); } if (parameterName.contains("RC_SCALE_AUX1")) { - rcScaling[5] = value.toInt(); + rcScaling[5] = value.toFloat(); } if (parameterName.contains("RC_SCALE_AUX2")) { - rcScaling[6] = value.toInt(); + rcScaling[6] = value.toFloat(); } if (parameterName.contains("RC_SCALE_AUX3")) { - rcScaling[7] = value.toInt(); + rcScaling[7] = value.toFloat(); } } @@ -575,45 +626,62 @@ void QGCVehicleConfig::updateView() { if (rc_mode == RC_MODE_1) { - ui->rollSlider->setValue(rcRoll); - ui->pitchSlider->setValue(rcThrottle); - ui->yawSlider->setValue(rcYaw); - ui->throttleSlider->setValue(rcPitch); + ui->rollSlider->setValue(rcRoll * 50 + 50); + ui->pitchSlider->setValue(rcThrottle * 100); + ui->yawSlider->setValue(rcYaw * 50 + 50); + ui->throttleSlider->setValue(rcPitch * 50 + 50); } else if (rc_mode == RC_MODE_2) { - ui->rollSlider->setValue(rcRoll); - ui->pitchSlider->setValue(rcPitch); - ui->yawSlider->setValue(rcYaw); - ui->throttleSlider->setValue(rcThrottle); + ui->rollSlider->setValue(rcRoll * 50 + 50); + ui->pitchSlider->setValue(rcPitch * 50 + 50); + ui->yawSlider->setValue(rcYaw * 50 + 50); + ui->throttleSlider->setValue(rcThrottle * 100); } else if (rc_mode == RC_MODE_3) { - ui->rollSlider->setValue(rcYaw); - ui->pitchSlider->setValue(rcThrottle); - ui->yawSlider->setValue(rcRoll); - ui->throttleSlider->setValue(rcPitch); + ui->rollSlider->setValue(rcYaw * 50 + 50); + ui->pitchSlider->setValue(rcThrottle * 100); + ui->yawSlider->setValue(rcRoll * 50 + 50); + ui->throttleSlider->setValue(rcPitch * 50 + 50); } else if (rc_mode == RC_MODE_4) { - ui->rollSlider->setValue(rcYaw); - ui->pitchSlider->setValue(rcPitch); - ui->yawSlider->setValue(rcRoll); - ui->throttleSlider->setValue(rcThrottle); + ui->rollSlider->setValue(rcYaw * 50 + 50); + ui->pitchSlider->setValue(rcPitch * 50 + 50); + ui->yawSlider->setValue(rcRoll * 50 + 50); + ui->throttleSlider->setValue(rcThrottle * 100); + } + + ui->chanLabel->setText(QString("%1/%2").arg(rcValue[rcMapping[0]]).arg(rcRoll, 5, 'f', 2, QChar(' '))); + ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[rcMapping[1]]).arg(rcPitch, 5, 'f', 2, QChar(' '))); + ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[rcMapping[2]]).arg(rcYaw, 5, 'f', 2, QChar(' '))); + ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[rcMapping[3]]).arg(rcThrottle, 5, 'f', 2, QChar(' '))); + + ui->modeSwitchSlider->setValue(rcMode * 50 + 50); + ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[rcMapping[4]]).arg(rcMode, 5, 'f', 2, QChar(' '))); + + if (rcValue[rcMapping[5]] != UINT16_MAX) { + ui->aux1Slider->setValue(rcAux1 * 50 + 50); + ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' '))); + } else { + ui->chanLabel_6->setText(tr("---")); + } + + if (rcValue[rcMapping[6]] != UINT16_MAX) { + ui->aux2Slider->setValue(rcAux2 * 50 + 50); + ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' '))); + } else { + ui->chanLabel_7->setText(tr("---")); + } + + if (rcValue[rcMapping[7]] != UINT16_MAX) { + ui->aux3Slider->setValue(rcAux3 * 50 + 50); + ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' '))); + } else { + ui->chanLabel_8->setText(tr("---")); } - ui->chanLabel->setText(QString("%1/%2").arg(rcValue[0]).arg(rcRoll)); - ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[1]).arg(rcPitch)); - ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[2]).arg(rcYaw)); - ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[3]).arg(rcThrottle)); - ui->modeSwitchSlider->setValue(rcMode); - ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[4]).arg(rcMode)); - ui->aux1Slider->setValue(rcAux1); - ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[5]).arg(rcAux1)); - ui->aux2Slider->setValue(rcAux2); - ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[6]).arg(rcAux2)); - ui->aux3Slider->setValue(rcAux3); - ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[7]).arg(rcAux3)); changed = false; } } diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h index caec352a16d2c76524477ae37c839002c07730c4..9069776ffdc1e9258571f0e9c77f8b8863010e96 100644 --- a/src/ui/QGCVehicleConfig.h +++ b/src/ui/QGCVehicleConfig.h @@ -37,11 +37,89 @@ public slots: void stopCalibrationRC(); /** Start/stop the RC calibration routine */ void toggleCalibrationRC(bool enabled); + /** Set trim positions */ + void setTrimPositions(); + /** Detect which channels need to be inverted */ + void detectChannelInversion(); /** Change the mode setting of the control inputs */ void setRCModeIndex(int newRcMode); /** Render the data updated */ void updateView(); + /** Set the RC channel */ + void setRollChan(int channel) { + rcMapping[0] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setPitchChan(int channel) { + rcMapping[1] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setYawChan(int channel) { + rcMapping[2] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setThrottleChan(int channel) { + rcMapping[3] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setModeChan(int channel) { + rcMapping[4] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setAux1Chan(int channel) { + rcMapping[5] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setAux2Chan(int channel) { + rcMapping[6] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + /** Set the RC channel */ + void setAux3Chan(int channel) { + rcMapping[7] = channel - 1; + updateInvertedCheckboxes(channel - 1); + } + + /** Set channel inversion status */ + void setRollInverted(bool inverted) { + rcRev[rcMapping[0]] = inverted; + } + /** Set channel inversion status */ + void setPitchInverted(bool inverted) { + rcRev[rcMapping[1]] = inverted; + } + /** Set channel inversion status */ + void setYawInverted(bool inverted) { + rcRev[rcMapping[2]] = inverted; + } + /** Set channel inversion status */ + void setThrottleInverted(bool inverted) { + rcRev[rcMapping[3]] = inverted; + } + /** Set channel inversion status */ + void setModeInverted(bool inverted) { + rcRev[rcMapping[4]] = inverted; + } + /** Set channel inversion status */ + void setAux1Inverted(bool inverted) { + rcRev[rcMapping[5]] = inverted; + } + /** Set channel inversion status */ + void setAux2Inverted(bool inverted) { + rcRev[rcMapping[6]] = inverted; + } + /** Set channel inversion status */ + void setAux3Inverted(bool inverted) { + rcRev[rcMapping[7]] = inverted; + } + protected slots: /** Reset the RC calibration */ void resetCalibrationRC(); @@ -60,16 +138,19 @@ protected slots: void setRCType(int type); /** Check timeouts */ void checktimeOuts(); + /** Update checkbox status */ + void updateInvertedCheckboxes(int index); protected: UASInterface* mav; ///< The current MAV static const unsigned int chanMax = 8; ///< Maximum number of channels + unsigned int chanCount; ///< Actual channels int rcType; ///< Type of the remote control quint64 rcTypeUpdateRequested; ///< Zero if not requested, non-zero if requested static const unsigned int rcTypeTimeout = 5000; ///< 5 seconds timeout, in milliseconds - int rcMin[chanMax]; ///< Minimum values - int rcMax[chanMax]; ///< Maximum values - int rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle) + float rcMin[chanMax]; ///< Minimum values + float rcMax[chanMax]; ///< Maximum values + float rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle) int rcMapping[chanMax]; ///< PWM to function mappings float rcScaling[chanMax]; ///< Scaling of channel input to control commands bool rcRev[chanMax]; ///< Channel reverse @@ -87,6 +168,7 @@ protected: QTimer updateTimer; ///< Controls update intervals enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention QList toolWidgets; ///< Configurable widgets + bool calibrationEnabled; ///< calibration mode on / off private: Ui::QGCVehicleConfig *ui; diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui index 89628d17c569e0e88ed2de2738524dd4bf33e019..2cda1d202143962dcaa92f1832fc855e1f00e203 100644 --- a/src/ui/QGCVehicleConfig.ui +++ b/src/ui/QGCVehicleConfig.ui @@ -40,7 +40,7 @@ - 1 + 0 @@ -53,10 +53,10 @@ - -1 + 0 - 1 + 100 0 @@ -69,10 +69,10 @@ - -1 + 0 - 1 + 100 0 @@ -595,10 +595,10 @@ - -1 + 0 - 1 + 100 0 @@ -611,10 +611,10 @@ - -1 + 0 - 1 + 100 0 @@ -650,10 +650,10 @@ - -1 + 0 - 1 + 100 Qt::Vertical @@ -663,10 +663,10 @@ - -1 + 0 - 1 + 100 Qt::Vertical @@ -676,10 +676,10 @@ - -1 + 0 - 1 + 100 Qt::Vertical @@ -689,10 +689,10 @@ - -1 + 0 - 1 + 100 Qt::Vertical @@ -712,6 +712,13 @@ + + + + Set Trim + + + @@ -815,8 +822,8 @@ p, li { white-space: pre-wrap; } 0 0 - 651 - 203 + 98 + 28 @@ -852,8 +859,8 @@ p, li { white-space: pre-wrap; } 0 0 - 651 - 204 + 98 + 28 @@ -899,8 +906,8 @@ p, li { white-space: pre-wrap; } 0 0 - 651 - 203 + 98 + 28 @@ -959,8 +966,8 @@ p, li { white-space: pre-wrap; } 0 0 - 651 - 204 + 98 + 28