From 9b6b5bc7293454fcfafe4694f185f7c8623f696b Mon Sep 17 00:00:00 2001 From: lilvinz Date: Fri, 21 Sep 2012 23:51:21 +0200 Subject: [PATCH 01/34] changed receiver constants to be all negative in order to allow valid channel values of 0 for dsm --- flight/PiOS/STM32F10x/pios_ppm.c | 4 ++-- flight/PiOS/STM32F4xx/pios_ppm.c | 4 ++-- flight/PiOS/inc/pios_rcvr.h | 6 +++--- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/flight/PiOS/STM32F10x/pios_ppm.c b/flight/PiOS/STM32F10x/pios_ppm.c index 64d1196f9..b47a2d6c2 100644 --- a/flight/PiOS/STM32F10x/pios_ppm.c +++ b/flight/PiOS/STM32F10x/pios_ppm.c @@ -145,8 +145,8 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { /* Flush counter variables */ - ppm_dev->CaptureValue[i] = 0; - ppm_dev->CaptureValueNewFrame[i] = 0; + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; } diff --git a/flight/PiOS/STM32F4xx/pios_ppm.c b/flight/PiOS/STM32F4xx/pios_ppm.c index e17b342b7..048377ebd 100644 --- a/flight/PiOS/STM32F4xx/pios_ppm.c +++ b/flight/PiOS/STM32F4xx/pios_ppm.c @@ -145,8 +145,8 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { /* Flush counter variables */ - ppm_dev->CaptureValue[i] = 0; - ppm_dev->CaptureValueNewFrame[i] = 0; + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; } diff --git a/flight/PiOS/inc/pios_rcvr.h b/flight/PiOS/inc/pios_rcvr.h index ab493cd35..6b74c9b52 100644 --- a/flight/PiOS/inc/pios_rcvr.h +++ b/flight/PiOS/inc/pios_rcvr.h @@ -42,11 +42,11 @@ extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel); /*! Define error codes for PIOS_RCVR_Get */ enum PIOS_RCVR_errors { /*! Indicates that a failsafe condition or missing receiver detected for that channel */ - PIOS_RCVR_TIMEOUT = 0, + PIOS_RCVR_TIMEOUT = -1, /*! Channel is invalid for this driver (usually out of range supported) */ - PIOS_RCVR_INVALID = -1, + PIOS_RCVR_INVALID = -2, /*! Indicates that the driver for this channel has not been initialized */ - PIOS_RCVR_NODRIVER = -2 + PIOS_RCVR_NODRIVER = -3 }; #endif /* PIOS_RCVR_H */ From 1169fb5617d92af6a907720bc9484818bf1b4bf7 Mon Sep 17 00:00:00 2001 From: lilvinz Date: Sat, 22 Sep 2012 09:45:47 +0200 Subject: [PATCH 02/34] added channel data init to gcsreceiver --- flight/PiOS/Common/pios_gcsrcvr.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/flight/PiOS/Common/pios_gcsrcvr.c b/flight/PiOS/Common/pios_gcsrcvr.c index eda2a94ed..e3e34db5b 100644 --- a/flight/PiOS/Common/pios_gcsrcvr.c +++ b/flight/PiOS/Common/pios_gcsrcvr.c @@ -121,6 +121,11 @@ extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id) if (!gcsrcvr_dev) return -1; + for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; i++) { + /* Flush channels */ + gcsreceiverdata.Channel[i] = PIOS_RCVR_TIMEOUT; + } + /* Register uavobj callback */ GCSReceiverConnectCallback (gcsreceiver_updated); From 47cc6216ac455ba0b7d9ff8a96e603bb14708b24 Mon Sep 17 00:00:00 2001 From: lilvinz Date: Sat, 22 Sep 2012 10:02:15 +0200 Subject: [PATCH 03/34] use constants for receivers and updated function description --- flight/PiOS/Common/pios_gcsrcvr.c | 9 ++++++++- flight/PiOS/STM32F10x/pios_ppm.c | 11 ++++++----- flight/PiOS/STM32F10x/pios_pwm.c | 11 ++++++----- flight/PiOS/STM32F10x/pios_sbus.c | 2 +- flight/PiOS/STM32F4xx/pios_ppm.c | 11 ++++++----- flight/PiOS/STM32F4xx/pios_pwm.c | 11 ++++++----- 6 files changed, 33 insertions(+), 22 deletions(-) diff --git a/flight/PiOS/Common/pios_gcsrcvr.c b/flight/PiOS/Common/pios_gcsrcvr.c index e3e34db5b..709eeef76 100644 --- a/flight/PiOS/Common/pios_gcsrcvr.c +++ b/flight/PiOS/Common/pios_gcsrcvr.c @@ -137,11 +137,18 @@ extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id) return 0; } +/** + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >=0 channel value + */ static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel) { if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) { /* channel is out of range */ - return -1; + return PIOS_RCVR_INVALID; } return (gcsreceiverdata.Channel[channel]); diff --git a/flight/PiOS/STM32F10x/pios_ppm.c b/flight/PiOS/STM32F10x/pios_ppm.c index b47a2d6c2..4893d56a9 100644 --- a/flight/PiOS/STM32F10x/pios_ppm.c +++ b/flight/PiOS/STM32F10x/pios_ppm.c @@ -200,11 +200,12 @@ out_fail: } /** -* Get the value of an input channel -* \param[in] Channel Number of the channel desired -* \output -1 Channel not available -* \output >0 Channel value -*/ + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >=0 channel value + */ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) { struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id; diff --git a/flight/PiOS/STM32F10x/pios_pwm.c b/flight/PiOS/STM32F10x/pios_pwm.c index 4e7c98b14..497a5d19b 100644 --- a/flight/PiOS/STM32F10x/pios_pwm.c +++ b/flight/PiOS/STM32F10x/pios_pwm.c @@ -170,11 +170,12 @@ out_fail: } /** -* Get the value of an input channel -* \param[in] Channel Number of the channel desired -* \output -1 Channel not available -* \output >0 Channel value -*/ + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >=0 channel value + */ static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel) { struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id; diff --git a/flight/PiOS/STM32F10x/pios_sbus.c b/flight/PiOS/STM32F10x/pios_sbus.c index 53730b16b..50d0480c3 100644 --- a/flight/PiOS/STM32F10x/pios_sbus.c +++ b/flight/PiOS/STM32F10x/pios_sbus.c @@ -166,7 +166,7 @@ out_fail: * \param[in] channel Number of the channel desired (zero based) * \output PIOS_RCVR_INVALID channel not available * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver - * \output >0 channel value + * \output >=0 channel value */ static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel) { diff --git a/flight/PiOS/STM32F4xx/pios_ppm.c b/flight/PiOS/STM32F4xx/pios_ppm.c index 048377ebd..9acaca017 100644 --- a/flight/PiOS/STM32F4xx/pios_ppm.c +++ b/flight/PiOS/STM32F4xx/pios_ppm.c @@ -200,11 +200,12 @@ out_fail: } /** -* Get the value of an input channel -* \param[in] Channel Number of the channel desired -* \output -1 Channel not available -* \output >0 Channel value -*/ + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >=0 channel value + */ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) { struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id; diff --git a/flight/PiOS/STM32F4xx/pios_pwm.c b/flight/PiOS/STM32F4xx/pios_pwm.c index 5bbec32aa..2c67ad465 100644 --- a/flight/PiOS/STM32F4xx/pios_pwm.c +++ b/flight/PiOS/STM32F4xx/pios_pwm.c @@ -170,11 +170,12 @@ out_fail: } /** -* Get the value of an input channel -* \param[in] Channel Number of the channel desired -* \output -1 Channel not available -* \output >0 Channel value -*/ + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >=0 channel value + */ static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel) { struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id; From ee146a89eb9442085533864ecb5ac7fe62d2a07d Mon Sep 17 00:00:00 2001 From: lilvinz Date: Sat, 22 Sep 2012 10:32:46 +0200 Subject: [PATCH 04/34] updated comments --- flight/PiOS/STM32F10x/pios_dsm.c | 2 +- flight/PiOS/STM32F4xx/pios_dsm.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/STM32F10x/pios_dsm.c b/flight/PiOS/STM32F10x/pios_dsm.c index cb838b56b..2dfaa1c3f 100644 --- a/flight/PiOS/STM32F10x/pios_dsm.c +++ b/flight/PiOS/STM32F10x/pios_dsm.c @@ -347,7 +347,7 @@ static uint16_t PIOS_DSM_RxInCallback(uint32_t context, * \param[in] channel Number of the channel desired (zero based) * \output PIOS_RCVR_INVALID channel not available * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver - * \output >0 channel value + * \output >=0 channel value */ static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel) { diff --git a/flight/PiOS/STM32F4xx/pios_dsm.c b/flight/PiOS/STM32F4xx/pios_dsm.c index 7c5348560..06bc27476 100644 --- a/flight/PiOS/STM32F4xx/pios_dsm.c +++ b/flight/PiOS/STM32F4xx/pios_dsm.c @@ -349,7 +349,7 @@ static uint16_t PIOS_DSM_RxInCallback(uint32_t context, * \param[in] channel Number of the channel desired (zero based) * \output PIOS_RCVR_INVALID channel not available * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver - * \output >0 channel value + * \output >=0 channel value */ static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel) { From 5132448fe810c127290ccfae9ba6f70b7c3884f6 Mon Sep 17 00:00:00 2001 From: Erik Gustavsson Date: Thu, 29 Nov 2012 18:50:25 +0100 Subject: [PATCH 05/34] Decrease zeroing yawBiasRate to reduce noise-induced random yaw drift. --- flight/Modules/Attitude/attitude.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 7f43eb7a7..02c511500 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -218,14 +218,14 @@ static void AttitudeTask(void *parameters) // For first 7 seconds use accels to get gyro bias accelKp = 1; accelKi = 0.9; - yawBiasRate = 0.23; + yawBiasRate = 0.01; accel_filter_enabled = false; init = 0; } else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { accelKp = 1; accelKi = 0.9; - yawBiasRate = 0.23; + yawBiasRate = 0.01; accel_filter_enabled = false; init = 0; } else if (init == 0) { From 45a3bb975c41d9e9ab482ce41e2833fad357362b Mon Sep 17 00:00:00 2001 From: Kevin Vertucio Date: Tue, 19 Mar 2013 10:14:50 -0400 Subject: [PATCH 06/34] OP-791 FIXED issue where Flickable web view would need to be dragged to scroll content Replaced Flickable component with ListView for the Authors list. Signed-off-by: Kevin Vertucio --- .../src/plugins/coreplugin/core.qrc | 3 +- .../plugins/coreplugin/qml/AboutDialog.qml | 57 ++--- .../plugins/coreplugin/qml/AuthorsModel.qml | 151 ++++++++++++++ .../coreplugin/qml/FlickableWebView.qml | 196 ------------------ .../coreplugin/qml/ScrollDecorator.qml | 40 ++++ 5 files changed, 223 insertions(+), 224 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/qml/AuthorsModel.qml delete mode 100644 ground/openpilotgcs/src/plugins/coreplugin/qml/FlickableWebView.qml create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/qml/ScrollDecorator.qml diff --git a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc index 85ca549e6..268eb4808 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc +++ b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc @@ -64,7 +64,8 @@ images/tx-rx.svg qml/images/tab.png qml/AboutDialog.qml - qml/FlickableWebView.qml + qml/AuthorsModel.qml + qml/ScrollDecorator.qml qml/TabWidget.qml diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml index a1be53bc5..502771267 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml @@ -41,8 +41,12 @@ import QtQuick 1.1 import QtWebKit 1.0 + // This is a tabbed pane element. Add a nested Rectangle to add a tab. TabWidget { + // Define AuthorsModel as type + property AuthorsModel authors: AuthorsModel {} + id: tabs width: 640; height: 480 // This tab is for the GCS version information @@ -75,35 +79,34 @@ } } } - // This is a stub for the Plugins. - // Rectangle { - // property string title: "Plugins" - // anchors.fill: parent - // color: "#e3e3e3" - // - // Rectangle { - // anchors.fill: parent; anchors.margins: 20 - // color: "#7fff7f" - // Text { - // width: parent.width - 20 - // anchors.centerIn: parent; horizontalAlignment: Qt.AlignHCenter - // font.pixelSize: 20 - // wrapMode: Text.WordWrap - // } - // } - // } - // This tab is for the authors/contributors/credits + // This tab is for the authors/contributors/credits Rectangle { property string title: "Authors" anchors.fill: parent; color: "#e3e3e3" - Rectangle { + Rectangle { anchors.fill: parent; anchors.margins: 20 color: "#e3e3e3" - FlickableWebView { - id: webView - z: 0 - url: "../CREDITS.html" - anchors { top: parent.top; left: parent.left; right: parent.right; bottom: parent.bottom } - } - } - } \ No newline at end of file + Text { + id: description + text: "

These people have been key contributors to the OpenPilot project. Without the work of the people in this list, OpenPilot would not be what it is today.

This list is sorted alphabetically by name

" + width: 600 + wrapMode: Text.WordWrap + + } + ListView { + id: authorsView + y: description.y + description.height + 20 + width: parent.width; height: parent.height - description.height - 20 + spacing: 3 + model: authors + delegate: Text { + text: name + } + clip: true + } + ScrollDecorator { + flickableItem: authorsView + } + } + } +} \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/AuthorsModel.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/AuthorsModel.qml new file mode 100644 index 000000000..b55ee86e9 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/AuthorsModel.qml @@ -0,0 +1,151 @@ +/* +This list model was created for the AuthorsDialog. +*/ +import QtQuick 1.1 + +ListModel { + + ListElement{ name:"Connor Abbott" } + + ListElement{ name:"David Ankers" } + + ListElement{ name:"Sergiy Anikeyev" } + + ListElement{ name:"Pedro Assuncao" } + + ListElement{ name:"Fredrik Arvidsson" } + + ListElement{ name:"Werner Backes" } + + ListElement{ name:"Jose Barros" } + + ListElement{ name:"Pete Boehl" } + + ListElement{ name:"David Carlson" } + + ListElement{ name:"James Cotton" } + + ListElement{ name:"Steve Doll" } + + ListElement{ name:"Piotr Esden-Tempski" } + + ListElement{ name:"Richard Flay" } + + ListElement{ name:"Peter Farnworth" } + + ListElement{ name:"Ed Faulkner" } + + ListElement{ name:"Darren Furniss" } + + ListElement{ name:"Frederic Goddeeris" } + + ListElement{ name:"Daniel Godin" } + + ListElement{ name:"Bani Greyling" } + + ListElement{ name:"Nuno Guedes" } + + ListElement{ name:"Erik Gustavsson" } + + ListElement{ name:"Peter Gunnarsson" } + + ListElement{ name:"Dean Hall" } + + ListElement{ name:"Joe Hlebasko" } + + ListElement{ name:"Andy Honecker" } + + ListElement{ name:"Ryan Hunt" } + + ListElement{ name:"Mark James" } + + ListElement{ name:"Sami Korhonen" } + + ListElement{ name:"Thorsten Klose" } + + ListElement{ name:"Hallvard Kristiansen" } + + ListElement{ name:"Edouard Lafargue" } + + ListElement{ name:"Mike Labranche" } + + ListElement{ name:"Fredrik Larsson" } + + ListElement{ name:"Pablo Lema" } + + ListElement{ name:"David Llama" } + + ListElement{ name:"Matt Lipski" } + + ListElement{ name:"Les Newell" } + + ListElement{ name:"Ken Northup" } + + ListElement{ name:"Greg Matthews" } + + ListElement{ name:"Guy McCaldin" } + + ListElement{ name:"Gary Mortimer" } + + ListElement{ name:"Alessio Morale" } + + ListElement{ name:"Cathy Moss" } + + ListElement{ name:"Angus Peart" } + + ListElement{ name:"Dmytro Poplavskiy" } + + ListElement{ name:"Eric Price" } + + ListElement{ name:"Richard Querin" } + + ListElement{ name:"Randy Ram" } + + ListElement{ name:"Laurent Ribon" } + + ListElement{ name:"Julien Rouviere" } + + ListElement{ name:"Jackson Russell" } + + ListElement{ name:"Zik Saleeba" } + + ListElement{ name:"Professor Dale Schinstock" } + + ListElement{ name:"Professor Kenn Sebesta" } + + ListElement{ name:"Oleg Semyonov" } + + ListElement{ name:"Stacey Sheldon" } + + ListElement{ name:"Troy Schultz" } + + ListElement{ name:"Dr. Erhard Siegl" } + + ListElement{ name:"Mike Smith" } + + ListElement{ name:"Alex Sowa" } + + ListElement{ name:"Pete Stapley" } + + ListElement{ name:"Rowan Taubitz" } + + ListElement{ name:"Andrew Thoms" } + + ListElement{ name:"Jasper van Loenen" } + + ListElement{ name:"Vassilis Varveropoulos" } + + ListElement{ name:"Kevin Vertucio" } + + ListElement{ name:"Alex Vrubel" } + + ListElement{ name:"Brian Webb" } + + ListElement{ name:"Justin Welander" } + + ListElement{ name:"Mat Wellington" } + + ListElement{ name:"Kendal Wells" } + + ListElement{ name:"Dmitriy Zaitsev" } +} \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/FlickableWebView.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/FlickableWebView.qml deleted file mode 100644 index 3043ce88a..000000000 --- a/ground/openpilotgcs/src/plugins/coreplugin/qml/FlickableWebView.qml +++ /dev/null @@ -1,196 +0,0 @@ -/**************************************************************************** -** -** Copyright (C) 2012 Nokia Corporation and/or its subsidiary(-ies). -** Contact: http://www.qt-project.org/ -** -** This file is part of the QtDeclarative module of the Qt Toolkit. -** -** $QT_BEGIN_LICENSE:LGPL$ -** GNU Lesser General Public License Usage -** This file may be used under the terms of the GNU Lesser General Public -** License version 2.1 as published by the Free Software Foundation and -** appearing in the file LICENSE.LGPL included in the packaging of this -** file. Please review the following information to ensure the GNU Lesser -** General Public License version 2.1 requirements will be met: -** http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html. -** -** In addition, as a special exception, Nokia gives you certain additional -** rights. These rights are described in the Nokia Qt LGPL Exception -** version 1.1, included in the file LGPL_EXCEPTION.txt in this package. -** -** GNU General Public License Usage -** Alternatively, this file may be used under the terms of the GNU General -** Public License version 3.0 as published by the Free Software Foundation -** and appearing in the file LICENSE.GPL included in the packaging of this -** file. Please review the following information to ensure the GNU General -** Public License version 3.0 requirements will be met: -** http://www.gnu.org/copyleft/gpl.html. -** -** Other Usage -** Alternatively, this file may be used in accordance with the terms and -** conditions contained in a signed written agreement between you and Nokia. -** -** -** -** -** -** -** $QT_END_LICENSE$ -** -****************************************************************************/ - -import QtQuick 1.0 -import QtWebKit 1.0 - -Flickable { - property alias title: webView.title - property alias icon: webView.icon - property alias progress: webView.progress - property alias url: webView.url - property alias back: webView.back - property alias stop: webView.stop - property alias reload: webView.reload - property alias forward: webView.forward - - id: flickable - width: parent.width - contentWidth: Math.max(parent.width,webView.width) - contentHeight: Math.max(parent.height,webView.height) - // anchors.top: headerSpace.bottom - anchors.bottom: parent.top - anchors.left: parent.left - anchors.right: parent.right - pressDelay: 200 - clip: true - - onWidthChanged : { - // Expand (but not above 1:1) if otherwise would be smaller that available width. - if (width > webView.width*webView.contentsScale && webView.contentsScale < 1.0) - webView.contentsScale = width / webView.width * webView.contentsScale; - } - - WebView { - id: webView - transformOrigin: Item.TopLeft - - function fixUrl(url) - { - if (url == "") return url - if (url[0] == "/") return "file://"+url - if (url.indexOf(":")<0) { - if (url.indexOf(".")<0 || url.indexOf(" ")>=0) { - // Fall back to a search engine; hard-code Wikipedia - return "http://en.wikipedia.org/w/index.php?search="+url - } else { - return "http://"+url - } - } - return url - } - - url: fixUrl(webBrowser.urlString) - smooth: false // We don't want smooth scaling, since we only scale during (fast) transitions - focus: true - - onAlert: console.log(message) - - function doZoom(zoom,centerX,centerY) - { - if (centerX) { - var sc = zoom*contentsScale; - scaleAnim.to = sc; - flickVX.from = flickable.contentX - flickVX.to = Math.max(0,Math.min(centerX-flickable.width/2,webView.width*sc-flickable.width)) - finalX.value = flickVX.to - flickVY.from = flickable.contentY - flickVY.to = Math.max(0,Math.min(centerY-flickable.height/2,webView.height*sc-flickable.height)) - finalY.value = flickVY.to - quickZoom.start() - } - } - - Keys.onLeftPressed: webView.contentsScale -= 0.1 - Keys.onRightPressed: webView.contentsScale += 0.1 - - preferredWidth: flickable.width - preferredHeight: flickable.height - contentsScale: 1 - onContentsSizeChanged: { - // zoom out - contentsScale = Math.min(1,flickable.width / contentsSize.width) - } - onUrlChanged: { - // got to topleft - flickable.contentX = 0 - flickable.contentY = 0 - // if (url != null) { header.editUrl = url.toString(); } - } - onDoubleClick: { - if (!heuristicZoom(clickX,clickY,2.5)) { - var zf = flickable.width / contentsSize.width - if (zf >= contentsScale) - zf = 2.0*contentsScale // zoom in (else zooming out) - doZoom(zf,clickX*zf,clickY*zf) - } - } - - SequentialAnimation { - id: quickZoom - - PropertyAction { - target: webView - property: "renderingEnabled" - value: false - } - ParallelAnimation { - NumberAnimation { - id: scaleAnim - target: webView - property: "contentsScale" - // the to property is set before calling - easing.type: Easing.Linear - duration: 200 - } - NumberAnimation { - id: flickVX - target: flickable - property: "contentX" - easing.type: Easing.Linear - duration: 200 - from: 0 // set before calling - to: 0 // set before calling - } - NumberAnimation { - id: flickVY - target: flickable - property: "contentY" - easing.type: Easing.Linear - duration: 200 - from: 0 // set before calling - to: 0 // set before calling - } - } - // Have to set the contentXY, since the above 2 - // size changes may have started a correction if - // contentsScale < 1.0. - PropertyAction { - id: finalX - target: flickable - property: "contentX" - value: 0 // set before calling - } - PropertyAction { - id: finalY - target: flickable - property: "contentY" - value: 0 // set before calling - } - PropertyAction { - target: webView - property: "renderingEnabled" - value: true - } - } - onZoomTo: doZoom(zoom,centerX,centerY) - } -} diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/ScrollDecorator.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/ScrollDecorator.qml new file mode 100644 index 000000000..24c79c927 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/ScrollDecorator.qml @@ -0,0 +1,40 @@ +import QtQuick 1.1 + +Rectangle { + id: scrollDecorator + + property Flickable flickableItem: null + + Loader { + id: scrollLoader + sourceComponent: scrollDecorator.flickableItem ? scrollBar : undefined + } + + Component.onDestruction: scrollLoader.sourceComponent = undefined + + Component { + id: scrollBar + Rectangle { + property Flickable flickable: scrollDecorator.flickableItem + + parent: flickable + anchors.right: parent.right + + smooth: true + radius: 2 + color: "gray" + border.color: "lightgray" + border.width: 1.0 + opacity: flickable.moving ? 0.8 : 0.4 + + Behavior on opacity { + NumberAnimation { duration: 500 } + } + + width: 4 + height: flickable.height * (flickable.height / flickable.contentHeight) + y: flickable.height * (flickable.contentY / flickable.contentHeight) + visible: flickable.height < flickable.contentHeight + } + } +} From 45b0e787a4cc409ae1d2daa5a96bdcb924e11b26 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sat, 30 Mar 2013 19:57:16 +0100 Subject: [PATCH 07/34] OP-886 Improvements to sanitychecks Added an Extensions to Alarm for detailed status/substatus reporting. Extended Alarms are the first in the Alarm structure and have corresponding fields in Status and Substatus structures. Also added a filter to the HWsettings update to prevent to block arming when actual settings have not changed. +review OPReview --- .../System => Libraries}/alarms.c | 42 +++- .../System => Libraries}/inc/alarms.h | 1 + flight/Libraries/inc/sanitycheck.h | 13 +- flight/Libraries/sanitycheck.c | 64 +++--- flight/Modules/System/systemmod.c | 17 +- flight/targets/CopterControl/Makefile | 2 +- .../targets/CopterControl/System/inc/alarms.h | 50 ---- flight/targets/OSD/Makefile | 2 +- flight/targets/OSD/System/alarms.c | 210 ----------------- flight/targets/OSD/System/inc/alarms.h | 50 ---- flight/targets/PipXtreme/System/alarms.c | 214 ------------------ flight/targets/RevoMini/Makefile | 2 +- flight/targets/RevoMini/System/alarms.c | 210 ----------------- flight/targets/RevoMini/System/inc/alarms.h | 50 ---- flight/targets/Revolution/Makefile | 2 +- flight/targets/Revolution/System/alarms.c | 210 ----------------- flight/targets/Revolution/System/inc/alarms.h | 50 ---- flight/targets/SimPosix/Makefile | 2 +- flight/targets/SimPosix/System/alarms.c | 210 ----------------- flight/targets/SimPosix/System/inc/alarms.h | 50 ---- shared/uavobjectdefinition/systemalarms.xml | 18 +- 21 files changed, 123 insertions(+), 1346 deletions(-) rename flight/{targets/CopterControl/System => Libraries}/alarms.c (76%) rename flight/{targets/PipXtreme/System => Libraries}/inc/alarms.h (91%) mode change 100755 => 100644 delete mode 100644 flight/targets/CopterControl/System/inc/alarms.h delete mode 100644 flight/targets/OSD/System/alarms.c delete mode 100644 flight/targets/OSD/System/inc/alarms.h delete mode 100755 flight/targets/PipXtreme/System/alarms.c delete mode 100644 flight/targets/RevoMini/System/alarms.c delete mode 100644 flight/targets/RevoMini/System/inc/alarms.h delete mode 100644 flight/targets/Revolution/System/alarms.c delete mode 100644 flight/targets/Revolution/System/inc/alarms.h delete mode 100644 flight/targets/SimPosix/System/alarms.c delete mode 100644 flight/targets/SimPosix/System/inc/alarms.h diff --git a/flight/targets/CopterControl/System/alarms.c b/flight/Libraries/alarms.c similarity index 76% rename from flight/targets/CopterControl/System/alarms.c rename to flight/Libraries/alarms.c index 01d79a1e5..6f5d53d8b 100644 --- a/flight/targets/CopterControl/System/alarms.c +++ b/flight/Libraries/alarms.c @@ -87,6 +87,42 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity } +/** + * Set an Extended Alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @param status: the Extended alarm status field + * @param subStatus: the Extended alarm substatus field + * @return 0 if success, -1 if an error + */ +int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity, uint8_t status, uint8_t subStatus) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.ExtendedAlarmStatus[alarm] = status; + alarms.ExtendedAlarmSubStatus[alarm] = subStatus; + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; +} + /** * Get an alarm * @param alarm The system alarm to be read @@ -136,7 +172,11 @@ void AlarmsDefaultAll() */ int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) { - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); + if (alarm < SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM){ + return ExtendedAlarmsSet(alarm, SYSTEMALARMS_ALARM_OK, 0, 0); + } else { + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); + } } /** diff --git a/flight/targets/PipXtreme/System/inc/alarms.h b/flight/Libraries/inc/alarms.h old mode 100755 new mode 100644 similarity index 91% rename from flight/targets/PipXtreme/System/inc/alarms.h rename to flight/Libraries/inc/alarms.h index 9fb047dca..ad2522273 --- a/flight/targets/PipXtreme/System/inc/alarms.h +++ b/flight/Libraries/inc/alarms.h @@ -33,6 +33,7 @@ int32_t AlarmsInitialize(void); int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity, uint8_t status, uint8_t subStatus); SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); void AlarmsDefaultAll(); diff --git a/flight/Libraries/inc/sanitycheck.h b/flight/Libraries/inc/sanitycheck.h index 2f201da22..9ee72f3c5 100644 --- a/flight/Libraries/inc/sanitycheck.h +++ b/flight/Libraries/inc/sanitycheck.h @@ -29,6 +29,17 @@ #ifndef SANITYCHECK_H #define SANITYCHECK_H +#define SANITYCHECK_STATUS_ERROR_NONE 0 +#define SANITYCHECK_STATUS_ERROR_FLIGHTMODE 1 + +#define BOOTFAULT_STATUS_ERROR_NONE 0 +#define BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT 1 + +#if (SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM != SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM) || \ + (SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM > SYSTEMALARMS_ALARM_NUMELEM) +#error incongruent SystemAlarms. Please revise the UAVO definition in SystemAlarm.xml +#endif + extern int32_t configuration_check(); -#endif /* SANITYCHECK_H */ \ No newline at end of file +#endif /* SANITYCHECK_H */ diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index ab5cab3bf..18c73ea00 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -49,8 +49,9 @@ static int32_t check_stabilization_settings(int index, bool multirotor); */ int32_t configuration_check() { - int32_t status = SYSTEMALARMS_ALARM_OK; - + int32_t severity = SYSTEMALARMS_ALARM_OK; + uint8_t alarmstatus = SANITYCHECK_STATUS_ERROR_NONE; + uint8_t alarmsubstatus = 0; // Get board type const struct pios_board_info * bdinfo = &pios_board_info_blob; bool coptercontrol = bdinfo->board_type == 0x04; @@ -85,58 +86,61 @@ int32_t configuration_check() for(uint32_t i = 0; i < num_modes; i++) { switch(modes[i]) { case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL: - if (multirotor) - status = SYSTEMALARMS_ALARM_ERROR; + if (multirotor) { + severity = SYSTEMALARMS_ALARM_ERROR; + } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1: - status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : status; + severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : severity; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2: - status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : status; + severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : severity; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3: - status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : status; + severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : severity; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE: - if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) - status = SYSTEMALARMS_ALARM_ERROR; + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) { + severity = SYSTEMALARMS_ALARM_ERROR; + } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: - if (coptercontrol) - status = SYSTEMALARMS_ALARM_ERROR; - else { - // Revo supports altitude hold - if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) - status = SYSTEMALARMS_ALARM_ERROR; + if (coptercontrol) { + severity = SYSTEMALARMS_ALARM_ERROR; + } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) { // Revo supports altitude hold + severity = SYSTEMALARMS_ALARM_ERROR; } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL: - if (coptercontrol) - status = SYSTEMALARMS_ALARM_ERROR; - else { - // Revo supports altitude hold - if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) - status = SYSTEMALARMS_ALARM_ERROR; + if (coptercontrol) { + severity = SYSTEMALARMS_ALARM_ERROR; + } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold + severity = SYSTEMALARMS_ALARM_ERROR; } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD: - if (coptercontrol) - status = SYSTEMALARMS_ALARM_ERROR; - else { - // Revo supports altitude hold - if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) - status = SYSTEMALARMS_ALARM_ERROR; + if (coptercontrol){ + severity = SYSTEMALARMS_ALARM_ERROR; + } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold + severity = SYSTEMALARMS_ALARM_ERROR; } break; default: // Uncovered modes are automatically an error - status = SYSTEMALARMS_ALARM_ERROR; + severity = SYSTEMALARMS_ALARM_ERROR; } + // mark the first encountered erroneous setting in status and substatus + if(severity != SYSTEMALARMS_ALARM_OK && alarmstatus == SANITYCHECK_STATUS_ERROR_NONE) + { + alarmstatus = SANITYCHECK_STATUS_ERROR_FLIGHTMODE; + alarmsubstatus = i; + } + } // TODO: Check on a multirotor no axis supports "None" - if(status != SYSTEMALARMS_ALARM_OK) - AlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, status); + if(severity != SYSTEMALARMS_ALARM_OK) + ExtendedAlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, severity, alarmstatus, alarmsubstatus); else AlarmsClear(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION); diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 8d6e88508..b857baeac 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -49,6 +49,8 @@ #include "watchdogstatus.h" #include "taskmonitor.h" #include "hwsettings.h" +#include + //#define DEBUG_THIS_FILE @@ -85,6 +87,7 @@ static xTaskHandle systemTaskHandle; static xQueueHandle objectPersistenceQueue; static bool stackOverflow; static bool mallocFailed; +static HwSettingsData bootHwSettings; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); @@ -171,6 +174,8 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); + // Load a copy of HwSetting active at boot time + HwSettingsGet(&bootHwSettings); // Whenever the configuration changes, make sure it is safe to fly HwSettingsConnectCallback(hwSettingsUpdatedCb); @@ -303,9 +308,10 @@ static void objectUpdatedCb(UAVObjEvent * ev) retval = UAVObjDeleteMetaobjects(); } } else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_FULLERASE) { - retval = -1; #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) retval = PIOS_FLASHFS_Format(0); +#else + retval = -1; #endif } switch(retval) { @@ -328,7 +334,14 @@ static void objectUpdatedCb(UAVObjEvent * ev) */ static void hwSettingsUpdatedCb(UAVObjEvent * ev) { - AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR); + HwSettingsData currentHwSettings; + HwSettingsGet(¤tHwSettings); + // check whether the Hw Configuration has changed from the one used at boot time + if(!memcmp(&bootHwSettings,¤tHwSettings,sizeof(HwSettingsData))){ + return; + } + + ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR,BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT, 0); } /** diff --git a/flight/targets/CopterControl/Makefile b/flight/targets/CopterControl/Makefile index 1db667a81..2867232a4 100644 --- a/flight/targets/CopterControl/Makefile +++ b/flight/targets/CopterControl/Makefile @@ -62,7 +62,7 @@ ifndef TESTAPP SRC += $(OPSYSTEM)/coptercontrol.c SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_usb_board_data.c - SRC += $(OPSYSTEM)/alarms.c + SRC += $(FLIGHTLIB)/alarms.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c diff --git a/flight/targets/CopterControl/System/inc/alarms.h b/flight/targets/CopterControl/System/inc/alarms.h deleted file mode 100644 index 9fb047dca..000000000 --- a/flight/targets/CopterControl/System/inc/alarms.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} - */ diff --git a/flight/targets/OSD/Makefile b/flight/targets/OSD/Makefile index 9ff2df65d..31fe6ee57 100644 --- a/flight/targets/OSD/Makefile +++ b/flight/targets/OSD/Makefile @@ -48,7 +48,7 @@ ifndef TESTAPP SRC += $(OPSYSTEM)/osd.c SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_usb_board_data.c - SRC += $(OPSYSTEM)/alarms.c + SRC += $(FLIGHTLIB)/alarms.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c diff --git a/flight/targets/OSD/System/alarms.c b/flight/targets/OSD/System/alarms.c deleted file mode 100644 index e61c7c1ea..000000000 --- a/flight/targets/OSD/System/alarms.c +++ /dev/null @@ -1,210 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - diff --git a/flight/targets/OSD/System/inc/alarms.h b/flight/targets/OSD/System/inc/alarms.h deleted file mode 100644 index b62bc531b..000000000 --- a/flight/targets/OSD/System/inc/alarms.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} - */ diff --git a/flight/targets/PipXtreme/System/alarms.c b/flight/targets/PipXtreme/System/alarms.c deleted file mode 100755 index 01d79a1e5..000000000 --- a/flight/targets/PipXtreme/System/alarms.c +++ /dev/null @@ -1,214 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - - lock = xSemaphoreCreateRecursiveMutex(); - //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that - //AlarmsClearAll(); - //AlarmsDefaultAll(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - diff --git a/flight/targets/RevoMini/Makefile b/flight/targets/RevoMini/Makefile index f432a535a..316853ad9 100644 --- a/flight/targets/RevoMini/Makefile +++ b/flight/targets/RevoMini/Makefile @@ -66,7 +66,7 @@ ifndef TESTAPP SRC += $(OPSYSTEM)/revolution.c SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_usb_board_data.c - SRC += $(OPSYSTEM)/alarms.c + SRC += $(FLIGHTLIB)/alarms.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c diff --git a/flight/targets/RevoMini/System/alarms.c b/flight/targets/RevoMini/System/alarms.c deleted file mode 100644 index e61c7c1ea..000000000 --- a/flight/targets/RevoMini/System/alarms.c +++ /dev/null @@ -1,210 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - diff --git a/flight/targets/RevoMini/System/inc/alarms.h b/flight/targets/RevoMini/System/inc/alarms.h deleted file mode 100644 index 9fb047dca..000000000 --- a/flight/targets/RevoMini/System/inc/alarms.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} - */ diff --git a/flight/targets/Revolution/Makefile b/flight/targets/Revolution/Makefile index 60ae27377..da79a2e86 100644 --- a/flight/targets/Revolution/Makefile +++ b/flight/targets/Revolution/Makefile @@ -66,7 +66,7 @@ ifndef TESTAPP SRC += $(OPSYSTEM)/revolution.c SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/pios_usb_board_data.c - SRC += $(OPSYSTEM)/alarms.c + SRC += $(FLIGHTLIB)/alarms.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c diff --git a/flight/targets/Revolution/System/alarms.c b/flight/targets/Revolution/System/alarms.c deleted file mode 100644 index e61c7c1ea..000000000 --- a/flight/targets/Revolution/System/alarms.c +++ /dev/null @@ -1,210 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - diff --git a/flight/targets/Revolution/System/inc/alarms.h b/flight/targets/Revolution/System/inc/alarms.h deleted file mode 100644 index 9fb047dca..000000000 --- a/flight/targets/Revolution/System/inc/alarms.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} - */ diff --git a/flight/targets/SimPosix/Makefile b/flight/targets/SimPosix/Makefile index 47b90c6ec..6b948a6fd 100644 --- a/flight/targets/SimPosix/Makefile +++ b/flight/targets/SimPosix/Makefile @@ -78,7 +78,7 @@ SRC += ${OUTDIR}/InitMods.c SRC += ${OPMODULEDIR}/System/systemmod.c SRC += $(OPSYSTEM)/simposix.c SRC += $(OPSYSTEM)/pios_board.c -SRC += $(OPSYSTEM)/alarms.c +SRC += $(FLIGHTLIB)/alarms.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c diff --git a/flight/targets/SimPosix/System/alarms.c b/flight/targets/SimPosix/System/alarms.c deleted file mode 100644 index 6ccd5fb62..000000000 --- a/flight/targets/SimPosix/System/alarms.c +++ /dev/null @@ -1,210 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - diff --git a/flight/targets/SimPosix/System/inc/alarms.h b/flight/targets/SimPosix/System/inc/alarms.h deleted file mode 100644 index 0f0faeb8f..000000000 --- a/flight/targets/SimPosix/System/inc/alarms.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program 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. - * - * This program 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 this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} - */ diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index 82da544e2..8780d031d 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -1,12 +1,13 @@ - Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules.Some modules may have a module defined Status and Substatus fields that details its condition + SystemConfiguration + BootFault OutOfMemory StackOverflow CPUOverload - SystemConfiguration EventSystem Telemetry ManualControl @@ -19,10 +20,21 @@ FlightTime I2C GPS - BootFault Power + + + SystemConfiguration + BootFault + + + + + SystemConfiguration + BootFault + + From 23c0c3585c395e932049724d64a65cc83833515a Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Mon, 1 Apr 2013 16:41:12 +0200 Subject: [PATCH 08/34] OP-886 Fixes to styles and includes +review OPReview-430 --- flight/Libraries/alarms.c | 47 +++++++++++++++++-------------- flight/Libraries/sanitycheck.c | 16 +++++++---- flight/Modules/System/systemmod.c | 31 ++++++++++---------- 3 files changed, 52 insertions(+), 42 deletions(-) diff --git a/flight/Libraries/alarms.c b/flight/Libraries/alarms.c index 6f5d53d8b..2e79a156a 100644 --- a/flight/Libraries/alarms.c +++ b/flight/Libraries/alarms.c @@ -28,7 +28,7 @@ */ #include "openpilot.h" -#include "alarms.h" +#include "inc/alarms.h" // Private constants @@ -71,7 +71,10 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity } // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); + if(xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0){ + return -1; + } + // Read alarm and update its severity only if it was changed SystemAlarmsGet(&alarms); @@ -99,28 +102,30 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions { SystemAlarmsData alarms; - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) - { - return -1; - } + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) + { + return -1; + } - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); + // Lock + if(xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0){ + return -1; + } - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.ExtendedAlarmStatus[alarm] = status; - alarms.ExtendedAlarmSubStatus[alarm] = subStatus; - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if (alarms.Alarm[alarm] != severity) + { + alarms.ExtendedAlarmStatus[alarm] = status; + alarms.ExtendedAlarmSubStatus[alarm] = subStatus; + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; } /** diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 18c73ea00..b14fe30e6 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -26,13 +26,17 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "openpilot.h" -#include "taskmonitor.h" +#include #include -#include "sanitycheck.h" -#include "manualcontrolsettings.h" -#include "systemalarms.h" -#include "systemsettings.h" + +// Private includes +#include "inc/taskmonitor.h" +#include "inc/sanitycheck.h" + +// UAVOs +#include +#include +#include /**************************** * Current checks: diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index b857baeac..5e5769b8a 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -38,17 +38,20 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "openpilot.h" -#include "systemmod.h" -#include "objectpersistence.h" -#include "flightstatus.h" -#include "systemstats.h" -#include "systemsettings.h" -#include "i2cstats.h" -#include "taskinfo.h" -#include "watchdogstatus.h" -#include "taskmonitor.h" -#include "hwsettings.h" +#include +// private includes +#include "inc/systemmod.h" +// UAVOs +#include +#include +#include +#include +#include +#include +#include +#include +#include +// Flight Libraries #include @@ -337,11 +340,9 @@ static void hwSettingsUpdatedCb(UAVObjEvent * ev) HwSettingsData currentHwSettings; HwSettingsGet(¤tHwSettings); // check whether the Hw Configuration has changed from the one used at boot time - if(!memcmp(&bootHwSettings,¤tHwSettings,sizeof(HwSettingsData))){ - return; + if(memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0){ + ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR,BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT, 0); } - - ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR,BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT, 0); } /** From 8a83204715b9171faa093c79af7cc26f601bb7a8 Mon Sep 17 00:00:00 2001 From: Philippe Vanhaesendonck Date: Wed, 3 Apr 2013 18:29:31 +0200 Subject: [PATCH 09/34] Jira OP-678 -- remove sudo from debian post-install --- package/linux/deb_common/postinst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package/linux/deb_common/postinst b/package/linux/deb_common/postinst index df8022075..e58a3e1a3 100644 --- a/package/linux/deb_common/postinst +++ b/package/linux/deb_common/postinst @@ -20,7 +20,7 @@ set -e case "$1" in configure) - sudo udevadm control --reload-rules >&2 + /sbin/udevadm control --reload-rules >&2 ;; abort-upgrade|abort-remove|abort-deconfigure) From 13dd1178a8c48e4a9181c971534fd761e1e1006f Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 3 Apr 2013 19:26:25 +0200 Subject: [PATCH 10/34] OP-886 Fixes to styles: testing style settings for Eclipse +review OPReview-430 --- flight/Libraries/alarms.c | 102 +++++++------- flight/Libraries/sanitycheck.c | 240 ++++++++++++++++----------------- 2 files changed, 167 insertions(+), 175 deletions(-) diff --git a/flight/Libraries/alarms.c b/flight/Libraries/alarms.c index 2e79a156a..a2840004d 100644 --- a/flight/Libraries/alarms.c +++ b/flight/Libraries/alarms.c @@ -46,12 +46,12 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); int32_t AlarmsInitialize(void) { SystemAlarmsInitialize(); - - lock = xSemaphoreCreateRecursiveMutex(); - //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that - //AlarmsClearAll(); - //AlarmsDefaultAll(); - return 0; + + lock = xSemaphoreCreateRecursiveMutex(); + //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that + //AlarmsClearAll(); + //AlarmsDefaultAll(); + return 0; } /** @@ -62,26 +62,23 @@ int32_t AlarmsInitialize(void) */ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) { - SystemAlarmsData alarms; + SystemAlarmsData alarms; - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - if(xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0){ + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) { return -1; } + // Lock + if (xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0) { + return -1; + } // Read alarm and update its severity only if it was changed SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); + if (alarms.Alarm[alarm] != severity) { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); } // Release lock @@ -103,20 +100,18 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions SystemAlarmsData alarms; // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) - { + if (alarm >= SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) { return -1; } // Lock - if(xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0){ + if (xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0) { return -1; } // Read alarm and update its severity only if it was changed SystemAlarmsGet(&alarms); - if (alarms.Alarm[alarm] != severity) - { + if (alarms.Alarm[alarm] != severity) { alarms.ExtendedAlarmStatus[alarm] = status; alarms.ExtendedAlarmSubStatus[alarm] = subStatus; alarms.Alarm[alarm] = severity; @@ -135,13 +130,12 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions */ SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) { - SystemAlarmsData alarms; + SystemAlarmsData alarms; - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) { + return 0; + } // Read alarm SystemAlarmsGet(&alarms); @@ -155,7 +149,7 @@ SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) */ int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) { - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); } /** @@ -163,10 +157,9 @@ int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) */ void AlarmsDefaultAll() { - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { + AlarmsDefault(n); } } @@ -177,7 +170,7 @@ void AlarmsDefaultAll() */ int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) { - if (alarm < SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM){ + if (alarm < SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) { return ExtendedAlarmsSet(alarm, SYSTEMALARMS_ALARM_OK, 0, 0); } else { return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); @@ -189,10 +182,9 @@ int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) */ void AlarmsClearAll() { - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { + AlarmsClear(n); } } @@ -202,7 +194,7 @@ void AlarmsClearAll() */ int32_t AlarmsHasWarnings() { - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); } /** @@ -211,8 +203,9 @@ int32_t AlarmsHasWarnings() */ int32_t AlarmsHasErrors() { - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +} +; /** * Check if there are any alarms with critical or higher severity @@ -220,8 +213,9 @@ int32_t AlarmsHasErrors() */ int32_t AlarmsHasCritical() { - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +} +; /** * Check if there are any alarms with the given or higher severity @@ -229,23 +223,21 @@ int32_t AlarmsHasCritical() */ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) { - SystemAlarmsData alarms; - uint32_t n; + SystemAlarmsData alarms; + uint32_t n; - // Lock + // Lock xSemaphoreTakeRecursive(lock, portMAX_DELAY); // Read alarms SystemAlarmsGet(&alarms); // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { + if (alarms.Alarm[n] >= severity) { + xSemaphoreGiveRecursive(lock); + return 1; + } } // If this point is reached then no alarms found diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index b14fe30e6..c98369597 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -53,102 +53,102 @@ static int32_t check_stabilization_settings(int index, bool multirotor); */ int32_t configuration_check() { - int32_t severity = SYSTEMALARMS_ALARM_OK; - uint8_t alarmstatus = SANITYCHECK_STATUS_ERROR_NONE; - uint8_t alarmsubstatus = 0; - // Get board type - const struct pios_board_info * bdinfo = &pios_board_info_blob; - bool coptercontrol = bdinfo->board_type == 0x04; + int32_t severity = SYSTEMALARMS_ALARM_OK; + uint8_t alarmstatus = SANITYCHECK_STATUS_ERROR_NONE; + uint8_t alarmsubstatus = 0; + // Get board type + const struct pios_board_info * bdinfo = &pios_board_info_blob; + bool coptercontrol = bdinfo->board_type == 0x04; - // Classify airframe type - bool multirotor = true; - uint8_t airframe_type; - SystemSettingsAirframeTypeGet(&airframe_type); - switch(airframe_type) { - case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: - case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX: - case SYSTEMSETTINGS_AIRFRAMETYPE_TRI: - multirotor = true; - break; - default: - multirotor = false; - } + // Classify airframe type + bool multirotor = true; + uint8_t airframe_type; + SystemSettingsAirframeTypeGet(&airframe_type); + switch(airframe_type) { + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX: + case SYSTEMSETTINGS_AIRFRAMETYPE_TRI: + multirotor = true; + break; + default: + multirotor = false; + } - // For each available flight mode position sanity check the available - // modes - uint8_t num_modes; - uint8_t modes[MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM]; - ManualControlSettingsFlightModeNumberGet(&num_modes); - ManualControlSettingsFlightModePositionGet(modes); + // For each available flight mode position sanity check the available + // modes + uint8_t num_modes; + uint8_t modes[MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM]; + ManualControlSettingsFlightModeNumberGet(&num_modes); + ManualControlSettingsFlightModePositionGet(modes); - for(uint32_t i = 0; i < num_modes; i++) { - switch(modes[i]) { - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL: - if (multirotor) { - severity = SYSTEMALARMS_ALARM_ERROR; - } - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1: - severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : severity; - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2: - severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : severity; - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3: - severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : severity; - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE: - if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) { - severity = SYSTEMALARMS_ALARM_ERROR; - } - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: - if (coptercontrol) { - severity = SYSTEMALARMS_ALARM_ERROR; - } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) { // Revo supports altitude hold - severity = SYSTEMALARMS_ALARM_ERROR; - } - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL: - if (coptercontrol) { - severity = SYSTEMALARMS_ALARM_ERROR; - } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold - severity = SYSTEMALARMS_ALARM_ERROR; - } - break; - case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD: - if (coptercontrol){ - severity = SYSTEMALARMS_ALARM_ERROR; - } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold - severity = SYSTEMALARMS_ALARM_ERROR; - } - break; - default: - // Uncovered modes are automatically an error - severity = SYSTEMALARMS_ALARM_ERROR; - } - // mark the first encountered erroneous setting in status and substatus - if(severity != SYSTEMALARMS_ALARM_OK && alarmstatus == SANITYCHECK_STATUS_ERROR_NONE) - { - alarmstatus = SANITYCHECK_STATUS_ERROR_FLIGHTMODE; - alarmsubstatus = i; - } + for(uint32_t i = 0; i < num_modes; i++) { + switch(modes[i]) { + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL: + if (multirotor) { + severity = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1: + severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : severity; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2: + severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : severity; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3: + severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : severity; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE: + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) { + severity = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: + if (coptercontrol) { + severity = SYSTEMALARMS_ALARM_ERROR; + } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) { // Revo supports altitude hold + severity = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL: + if (coptercontrol) { + severity = SYSTEMALARMS_ALARM_ERROR; + } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold + severity = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD: + if (coptercontrol){ + severity = SYSTEMALARMS_ALARM_ERROR; + } else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold + severity = SYSTEMALARMS_ALARM_ERROR; + } + break; + default: + // Uncovered modes are automatically an error + severity = SYSTEMALARMS_ALARM_ERROR; + } + // mark the first encountered erroneous setting in status and substatus + if(severity != SYSTEMALARMS_ALARM_OK && alarmstatus == SANITYCHECK_STATUS_ERROR_NONE) + { + alarmstatus = SANITYCHECK_STATUS_ERROR_FLIGHTMODE; + alarmsubstatus = i; + } - } + } - // TODO: Check on a multirotor no axis supports "None" - if(severity != SYSTEMALARMS_ALARM_OK) - ExtendedAlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, severity, alarmstatus, alarmsubstatus); - else - AlarmsClear(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION); + // TODO: Check on a multirotor no axis supports "None" + if(severity != SYSTEMALARMS_ALARM_OK) + ExtendedAlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, severity, alarmstatus, alarmsubstatus); + else + AlarmsClear(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION); - return 0; + return 0; } /** @@ -159,39 +159,39 @@ int32_t configuration_check() */ static int32_t check_stabilization_settings(int index, bool multirotor) { - // Make sure the modes have identical sizes - if (MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NUMELEM || - MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NUMELEM) - return SYSTEMALARMS_ALARM_ERROR; + // Make sure the modes have identical sizes + if (MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NUMELEM || + MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NUMELEM) + return SYSTEMALARMS_ALARM_ERROR; - uint8_t modes[MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM]; + uint8_t modes[MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM]; - // Get the different axis modes for this switch position - switch(index) { - case 1: - ManualControlSettingsStabilization1SettingsGet(modes); - break; - case 2: - ManualControlSettingsStabilization2SettingsGet(modes); - break; - case 3: - ManualControlSettingsStabilization3SettingsGet(modes); - break; - default: - return SYSTEMALARMS_ALARM_ERROR; - } + // Get the different axis modes for this switch position + switch(index) { + case 1: + ManualControlSettingsStabilization1SettingsGet(modes); + break; + case 2: + ManualControlSettingsStabilization2SettingsGet(modes); + break; + case 3: + ManualControlSettingsStabilization3SettingsGet(modes); + break; + default: + return SYSTEMALARMS_ALARM_ERROR; + } - // For multirotors verify that nothing is set to "none" - if (multirotor) { - for(uint32_t i = 0; i < NELEMENTS(modes); i++) { - if (modes[i] == MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE) - return SYSTEMALARMS_ALARM_ERROR; - } - } + // For multirotors verify that nothing is set to "none" + if (multirotor) { + for(uint32_t i = 0; i < NELEMENTS(modes); i++) { + if (modes[i] == MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE) + return SYSTEMALARMS_ALARM_ERROR; + } + } - // Warning: This assumes that certain conditions in the XML file are met. That - // MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel - // and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE + // Warning: This assumes that certain conditions in the XML file are met. That + // MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel + // and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE - return SYSTEMALARMS_ALARM_OK; + return SYSTEMALARMS_ALARM_OK; } From 9c00fdcd31d6e904d73d1b9a1c1b5d809f5e377d Mon Sep 17 00:00:00 2001 From: Kevin Vertucio Date: Thu, 4 Apr 2013 07:04:14 -0400 Subject: [PATCH 11/34] removed dependency for QtWebKit in AboutDialog.qml --- ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml index 502771267..9ace9177c 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml @@ -39,7 +39,6 @@ ****************************************************************************/ import QtQuick 1.1 - import QtWebKit 1.0 // This is a tabbed pane element. Add a nested Rectangle to add a tab. From f30692836a4971a78a848d0bd06ce26c712a1765 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Thu, 4 Apr 2013 20:11:57 +0200 Subject: [PATCH 12/34] OP-886 Fixes to styles +review OPReview-430 --- flight/Libraries/alarms.c | 4 ++-- flight/Modules/System/systemmod.c | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/flight/Libraries/alarms.c b/flight/Libraries/alarms.c index a2840004d..c9cddee6d 100644 --- a/flight/Libraries/alarms.c +++ b/flight/Libraries/alarms.c @@ -205,7 +205,7 @@ int32_t AlarmsHasErrors() { return hasSeverity(SYSTEMALARMS_ALARM_ERROR); } -; + /** * Check if there are any alarms with critical or higher severity @@ -215,7 +215,7 @@ int32_t AlarmsHasCritical() { return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); } -; + /** * Check if there are any alarms with the given or higher severity diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 5e5769b8a..5de110488 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -340,8 +340,8 @@ static void hwSettingsUpdatedCb(UAVObjEvent * ev) HwSettingsData currentHwSettings; HwSettingsGet(¤tHwSettings); // check whether the Hw Configuration has changed from the one used at boot time - if(memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0){ - ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR,BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT, 0); + if (memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0) { + ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_ERROR, BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT, 0); } } From f260b2f56815279ecdba128fd9475bc85e427bf6 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 6 Apr 2013 19:01:12 +0300 Subject: [PATCH 13/34] OP-897: remove non-user-selectable modes from GCS dropdown lists Now all unsupported options are disabled. They will be reenabled when ready for end users. Still developers can set them using UAVObjBrowser. As a side effect, a bit changed UAVO XML definitions. The "limits" option now uses comma to separate rules, semicolon to separate elements. Was vice versa. OP-897 #resolve #comment Pushed for review +review OPReview --- .../src/plugins/config/configinputwidget.cpp | 18 +++---- .../src/plugins/uavobjects/uavobjectfield.cpp | 25 +++++++--- .../manualcontrolsettings.xml | 49 +++++++++++++++++-- .../stabilizationsettings.xml | 16 +++--- 4 files changed, 79 insertions(+), 29 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index e9c9f8708..9bce4d777 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -133,15 +133,15 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true); addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw"); - addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw",1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw",1,true); addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 85b0f721f..8ac7f6674 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -101,18 +101,27 @@ void UAVObjectField::constructorInitialize(const QString& name, const QString& u void UAVObjectField::limitsInitialize(const QString &limits) { - /// format - /// (TY)->type (EQ-equal;NE-not equal;BE-between;BI-bigger;SM-smaller) - /// (VALX)->value - /// %TY:VAL1:VAL2:VAL3,%TY,VAL1,VAL2,VAL3 - /// example: first element bigger than 3 and second element inside [2.3,5] - /// "%BI:3,%BE:2.3:5" + // Limit string format: + // % - start char + // XXXX - optional BOARD_TYPE and BOARD_REVISION (4 hex digits) + // TY - rule type (EQ-equal, NE-not equal, BE-between, BI-bigger, SM-smaller) + // VAL - values for TY separated by colon + // , - rule separator (may have leading or trailing spaces) + // ; - element separator (may have leading or trailing spaces) + // + // Examples: + // Disable few flight modes for Revo (00903): + // "%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner" + // Original CC board (rev 1), first element bigger than 3 and second element inside [2.3-5.0]: + // "%0401BI:3; %BE:2.3:5" + // Set applicable range [0-500] for 3 elements of array for all boards: + // "%BE:0:500; %BE:0:500; %BE:0:500" if(limits.isEmpty()) return; - QStringList stringPerElement=limits.split(","); + QStringList stringPerElement = limits.split(";"); quint32 index=0; foreach (QString str, stringPerElement) { - QStringList ruleList=str.split(";"); + QStringList ruleList = str.split(","); QList limitList; foreach(QString rule,ruleList) { diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index ccb7cb54e..17b85cf5f 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -20,13 +20,54 @@ - - - + + + - + + + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index b5c233fdc..06d5538e4 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -4,15 +4,15 @@ - - + + - - - - - - + + + + + + From 030cab376e7cd1b62530bfafaba4a3d7f6fc1b85 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sun, 7 Apr 2013 22:25:10 +0200 Subject: [PATCH 14/34] OP-879 move loading of factory default settings earlier (i.e. before any access to settings). In other words, factory default are now loaded from main.cpp instead of from mainwindow.cpp + minor formatting cleanups --- ground/openpilotgcs/src/app/main.cpp | 131 +++++++++++++----- .../src/plugins/coreplugin/mainwindow.cpp | 61 +------- 2 files changed, 98 insertions(+), 94 deletions(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index 98b93ff9a..1c3e64d59 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -78,6 +78,8 @@ static const char *EXIT_AFTER_CONFIG_OPTION = "-exit-after-config"; typedef QList PluginSpecSet; +static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml"; + // Helpers for displaying messages. Note that there is no console on Windows. #ifdef Q_OS_WIN // Format as
 HTML
@@ -204,36 +206,88 @@ static inline QStringList getPluginPaths()
     return rc;
 }
 
+static void loadFactorySettings(QSettings &settings)
+{
+    QDir directory(QCoreApplication::applicationDirPath());
 #ifdef Q_OS_MAC
-#  define SHARE_PATH "/../Resources"
+    directory.cdUp();
+    directory.cd("Resources");
 #else
-#  define SHARE_PATH "/../share/openpilotgcs"
+    directory.cdUp();
+    directory.cd("share");
+    directory.cd("openpilotgcs");
 #endif
+    directory.cd("default_configurations");
 
-static void overrideSettings(QSettings &settings, int argc, char **argv){
+    qDebug() << "Looking for configuration files in:" << directory.absolutePath();
 
-    QMap settingOptions;
+    QString filename;
+    // check if command line contains a config file name
+    QString commandLine;
+    foreach(QString str, qApp->arguments()) {
+        if (str.contains("configfile")) {
+            commandLine = str.split("=").at(1);
+        }
+    }
+    if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) {
+        // use file name specified on command line
+        filename = directory.absolutePath() + QDir::separator() + commandLine;
+        qDebug() << "Configuration file" << filename << "specified on command line will be loaded.";
+    } else if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) {
+        // use default file name
+        filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME;
+        qDebug() << "Default configuration file" << filename << "will be loaded.";
+    } else {
+        // TODO should we exit violently?
+        qWarning() << "No default configuration file found!";
+        return;
+    }
+
+    // create settings from file
+    QSettings *qs = new QSettings(filename, XmlConfig::XmlSettingsFormat);
+
+    // transfer loaded settings to application settings
+    QStringList keys = qs->allKeys();
+    foreach(QString key, keys) {
+        settings.setValue(key, qs->value(key));
+    }
+
+    // and delete loaded settings
+    delete qs;
+
+    qDebug() << "Configuration file" << filename << "was loaded.";
+}
+
+static void overrideSettings(QSettings &settings, int argc, char **argv)
+{
     // Options like -DMy/setting=test
     QRegExp rx("([^=]+)=(.*)");
 
-    for(int i = 0; i < argc; ++i ){
-        if ( QString(CONFIG_OPTION).compare(QString(argv[i])) == 0 ){
-            if ( rx.indexIn(argv[++i]) > -1 ){
+    QMap settingOptions;
+    for (int i = 0; i < argc; ++i) {
+        if (QString(CONFIG_OPTION).compare(QString(argv[i])) == 0) {
+            if (rx.indexIn(argv[++i]) > -1) {
                 settingOptions.insert(rx.cap(1), rx.cap(2));
             }
         }
-        if ( QString(CLEAN_CONFIG_OPTION).compare(QString(argv[i])) == 0 ){
+        if (QString(CLEAN_CONFIG_OPTION).compare(QString(argv[i])) == 0) {
             settings.clear();
         }
     }
 
     QList keys = settingOptions.keys();
-    foreach ( QString key, keys ){
+    foreach (QString key, keys) {
         settings.setValue(key, settingOptions.value(key));
     }
     settings.sync();
 }
 
+#ifdef Q_OS_MAC
+#  define SHARE_PATH "/../Resources"
+#else
+#  define SHARE_PATH "/../share/openpilotgcs"
+#endif
+
 int main(int argc, char **argv)
 {
     QElapsedTimer timer;
@@ -250,42 +304,52 @@ int main(int argc, char **argv)
     QApplication::setAttribute(Qt::AA_X11InitThreads, true);
 #endif
 
-    //Set the default locale to EN, if this is not set the system locale will be used
-    //and as of now we dont want that behaviour.
+    // Set the default locale to EN, if this is not set the system locale will be used
+    // and as of now we dont want that behaviour.
     QLocale::setDefault(QLocale::English);
 
     SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv);
 
-    //Open Splashscreen
+    // Open splash screen
     GCSSplashScreen splash;
     splash.show();
 
-    QString locale = QLocale::system().name();
-
     // Must be done before any QSettings class is created
     QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope,
-            QCoreApplication::applicationDirPath()+QLatin1String(SHARE_PATH));
+            QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH));
     // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp
-    QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope,
-                                 QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS_config"));
+    QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, QLatin1String("OpenPilot"),
+            QLatin1String("OpenPilotGCS_config"));
 
+    if (!settings.allKeys().count()) {
+        qDebug() << "No user setting, loading factory defaults.";
+        // no user settings, so try to load some default ones
+        loadFactorySettings(settings);
+    }
+
+    // override setting with command line provided settings
     overrideSettings(settings, argc, argv);
-    locale = settings.value("General/OverrideLanguage", locale).toString();
+
+    QString locale = QLocale::system().name();
+    qDebug() << "main - system locale:" << locale;
+
+    QString language = QLocale::system().name();
+    language = settings.value("General/OverrideLanguage", language).toString();
+    qDebug() << "main - language:" << language;
 
     QTranslator translator;
-    QTranslator qtTranslator;
-
-    const QString &creatorTrPath = QCoreApplication::applicationDirPath()
-                                   + QLatin1String(SHARE_PATH "/translations");
-    if (translator.load(QLatin1String("openpilotgcs_") + locale, creatorTrPath)) {
+    const QString &creatorTrPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH "/translations");
+    if (translator.load(QLatin1String("openpilotgcs_") + language, creatorTrPath)) {
         const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath);
-        const QString &qtTrFile = QLatin1String("qt_") + locale;
+        const QString &qtTrFile = QLatin1String("qt_") + language;
         // Binary installer puts Qt tr files into creatorTrPath
+        QTranslator qtTranslator;
         if (qtTranslator.load(qtTrFile, qtTrPath) || qtTranslator.load(qtTrFile, creatorTrPath)) {
             QCoreApplication::installTranslator(&translator);
             QCoreApplication::installTranslator(&qtTranslator);
         } else {
-            translator.load(QString()); // unload()
+            // unload()
+            translator.load(QString());
         }
     }
     app.setProperty("qtc_locale", locale); // Do we need this?
@@ -313,10 +377,7 @@ int main(int argc, char **argv)
         appOptions.insert(QLatin1String(CLEAN_CONFIG_OPTION), false);
         appOptions.insert(QLatin1String(EXIT_AFTER_CONFIG_OPTION), false);
         QString errorMessage;
-        if (!pluginManager.parseOptions(arguments,
-                                        appOptions,
-                                        &foundAppOptions,
-                                        &errorMessage)) {
+        if (!pluginManager.parseOptions(arguments, appOptions, &foundAppOptions, &errorMessage)) {
             displayError(errorMessage);
             printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager);
             return -1;
@@ -331,9 +392,10 @@ int main(int argc, char **argv)
             break;
         }
     }
-    if(!coreplugin){
+    if (!coreplugin) {
         QString nativePaths = QDir::toNativeSeparators(pluginPaths.join(QLatin1String(",")));
-        const QString reason = QCoreApplication::translate("Application", "Could not find 'Core.pluginspec' in %1").arg(nativePaths);
+        const QString reason = QCoreApplication::translate("Application", "Could not find 'Core.pluginspec' in %1").arg(
+                nativePaths);
         displayError(msgCoreLoadFailure(reason));
         return 1;
     }
@@ -356,8 +418,9 @@ int main(int argc, char **argv)
         return 0;
     }
     const bool isFirstInstance = !app.isRunning();
-    if (!isFirstInstance && foundAppOptions.contains(QLatin1String(CLIENT_OPTION)))
+    if (!isFirstInstance && foundAppOptions.contains(QLatin1String(CLIENT_OPTION))) {
         return sendArguments(app, pluginManager.arguments()) ? 0 : -1;
+    }
 
     QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)),
                      &splash, SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*)));
@@ -396,11 +459,11 @@ int main(int argc, char **argv)
     splash.showProgressMessage(QObject::tr("Application started."));
     QTimer::singleShot(1500, &splash, SLOT(close()));
 
-    qDebug() << "main() took" << timer.elapsed() << "ms";
+    qDebug() << "main - main took" << timer.elapsed() << "ms";
 
     int ret = app.exec();
 
-    qDebug() << "GCS ran for" << timer.elapsed() << "ms";
+    qDebug() << "main - GCS ran for" << timer.elapsed() << "ms";
 
     return ret;
 }
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
index c955fd7e3..86176c9b2 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
+++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
@@ -85,14 +85,12 @@
 #include 
 #include 
 #include 
-#include "dialogs/importsettings.h"
 #include 
 
 using namespace Core;
 using namespace Core::Internal;
 
 static const char *uriListMimeFormatC = "text/uri-list";
-static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml";
 
 enum { debugMainWindow = 0 };
 
@@ -269,66 +267,9 @@ void MainWindow::modeChanged(Core::IMode */*mode*/)
 void MainWindow::extensionsInitialized()
 {
     QSettings *qs = m_settings;
-    if (!qs->allKeys().count()) {
-        // no user settings, so try to load some default ones
-        QDir directory(QCoreApplication::applicationDirPath());
-#ifdef Q_OS_MAC
-        directory.cdUp();
-        directory.cd("Resources");
-#else
-        directory.cdUp();
-        directory.cd("share");
-        directory.cd("openpilotgcs");
-#endif
-        directory.cd("default_configurations");
-
-        qDebug() << "Looking for configuration files in:" << directory.absolutePath();
-
-        QString filename;
-        // check if command line contains a config file name
-        QString commandLine;
-        foreach(QString str, qApp->arguments()) {
-            if (str.contains("configfile")) {
-                commandLine = str.split("=").at(1);
-            }
-        }
-        if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) {
-            // use file name specified on command line
-            filename = directory.absolutePath() + QDir::separator() + commandLine;
-            qDebug() << "Configuration file" << filename << "specified on command line will be loaded.";
-        } else if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) {
-            // use default file name
-            filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME;
-            qDebug() << "Default configuration file" << filename << "will be loaded.";
-        } else {
-            // prompt user for default file name
-            qDebug() << "Default configuration file" << directory.absolutePath() << QDir::separator()
-                    << DEFAULT_CONFIG_FILENAME << "was not found.";
-            importSettings *dialog = new importSettings(this);
-            dialog->loadFiles(directory.absolutePath());
-            dialog->exec();
-            filename = dialog->choosenConfig();
-            delete dialog;
-            qDebug() << "Configuration file" << filename << "was selected and will be loaded.";
-        }
-
-        // create settings from file
-        qs = new QSettings(filename, XmlConfig::XmlSettingsFormat);
-
-        // transfer loaded settings to application settings
-        QStringList keys = qs->allKeys();
-        foreach(QString key, keys) {
-            m_settings->setValue(key, qs->value(key));
-        }
-
-        // and delete loaded settings
-        delete qs;
-        qs = m_settings;
-
-        qDebug() << "Configuration file" << filename << "was loaded.";
-    }
 
     qs->beginGroup("General");
+
     m_config_description = qs->value("Description", "none").toString();
     m_config_details = qs->value("Details", "none").toString();
     m_config_stylesheet = qs->value("StyleSheet", "none").toString();

From f6c94687fc34c2d0c60a6ff72540ac35b099921f Mon Sep 17 00:00:00 2001
From: Philippe Renon 
Date: Sun, 7 Apr 2013 22:28:13 +0200
Subject: [PATCH 15/34] OP-879 removed now unused importsettings dialog

---
 .../src/plugins/coreplugin/coreplugin.pro     | 19 +++--
 .../coreplugin/dialogs/importsettings.cpp     | 57 -------------
 .../coreplugin/dialogs/importsettings.h       | 35 --------
 .../coreplugin/dialogs/importsettings.ui      | 82 -------------------
 4 files changed, 13 insertions(+), 180 deletions(-)
 delete mode 100644 ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp
 delete mode 100644 ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.h
 delete mode 100644 ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.ui

diff --git a/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro b/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro
index 90ded4b4f..78f3c9f6b 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro
+++ b/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro
@@ -1,22 +1,27 @@
 TEMPLATE = lib
 TARGET = Core
 DEFINES += CORE_LIBRARY
+
 QT += declarative \
     xml \
     network \
     script \
     svg \
     sql 
+
 include(../../openpilotgcsplugin.pri)
 include(../../libs/utils/utils.pri)
 include(../../shared/scriptwrapper/scriptwrapper.pri)
 include(coreplugin_dependencies.pri)
+
 INCLUDEPATH += dialogs \
     uavgadgetmanager \
     actionmanager
+
 DEPENDPATH += dialogs \
     uavgadgetmanager \
     actionmanager
+
 SOURCES += mainwindow.cpp \
     tabpositionindicator.cpp \
     fancyactionbar.cpp \
@@ -64,8 +69,8 @@ SOURCES += mainwindow.cpp \
     workspacesettings.cpp \
     uavconfiginfo.cpp \
     authorsdialog.cpp \
-    telemetrymonitorwidget.cpp \
-    dialogs/importsettings.cpp
+    telemetrymonitorwidget.cpp
+
 HEADERS += mainwindow.h \
     tabpositionindicator.h \
     fancyactionbar.h \
@@ -126,20 +131,22 @@ HEADERS += mainwindow.h \
     uavconfiginfo.h \
     authorsdialog.h \
     iconfigurableplugin.h \
-    telemetrymonitorwidget.h \
-    dialogs/importsettings.h
+    telemetrymonitorwidget.h
+
 FORMS += dialogs/settingsdialog.ui \
     dialogs/shortcutsettings.ui \
     generalsettings.ui \
     uavgadgetoptionspage.ui \
-    workspacesettings.ui \
-    dialogs/importsettings.ui
+    workspacesettings.ui
+
 RESOURCES += core.qrc \
     fancyactionbar.qrc
+
 unix:!macx { 
     images.files = images/openpilot_logo_*.png
     images.files = images/qtcreator_logo_*.png
     images.path = /share/pixmaps
     INSTALLS += images
 }
+
 OTHER_FILES += Core.pluginspec
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp
deleted file mode 100644
index 715b95e88..000000000
--- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp
+++ /dev/null
@@ -1,57 +0,0 @@
-#include "importsettings.h"
-#include "ui_importsettings.h"
-#include 
-#include 
-#include 
-#include 
-
-importSettings::importSettings(QWidget *parent) :
-    QDialog(parent),
-    ui(new Ui::importSettings)
-{
-    ui->setupUi(this);
-    connect(ui->cbConfigs, SIGNAL(currentIndexChanged(int)), this, SLOT(updateDetails(int)));
-    connect(ui->btnLoad, SIGNAL(clicked()), this, SLOT(accept()));
-    QTimer::singleShot(500, this, SLOT(repaint()));
-}
-
-void importSettings::loadFiles(QString path)
-{
-    QDir myDir(path);
-    QStringList filters;
-    filters << "*.xml";
-    QStringList list = myDir.entryList(filters,QDir::Files);
-    int x = 0;
-    foreach(QString fileStr, list) {
-        fileInfo *info = new fileInfo;
-        QSettings settings(path+QDir::separator() + fileStr, XmlConfig::XmlSettingsFormat);
-        settings.beginGroup("General");
-        info->description = settings.value("Description", "None").toString();
-        info->details = settings.value("Details", "None").toString();
-        settings.endGroup();
-        info->file = path + QDir::separator() + fileStr;
-        configList.insert(x,info);
-        ui->cbConfigs->addItem(info->description, x);
-        ++x;
-    }
-}
-
-void importSettings::updateDetails(int index)
-{
-    fileInfo *info = configList.value(ui->cbConfigs->itemData(index).toInt());
-    ui->lblDetails->setText(info->details);
-}
-
-QString importSettings::choosenConfig()
-{
-    fileInfo *info = configList.value(ui->cbConfigs->itemData(ui->cbConfigs->currentIndex()).toInt());
-    return info->file;
-}
-
-importSettings::~importSettings()
-{
-    foreach(fileInfo * info,configList.values()) {
-        delete info;
-    }
-    delete ui;
-}
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.h b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.h
deleted file mode 100644
index 8bf5f303f..000000000
--- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.h
+++ /dev/null
@@ -1,35 +0,0 @@
-
-#ifndef IMPORTSETTINGS_H
-#define IMPORTSETTINGS_H
-
-#include 
-#include 
-namespace Ui {
-class importSettings;
-}
-
-class importSettings : public QDialog
-{
-    Q_OBJECT
-    struct fileInfo {
-        QString file;
-        QString description;
-        QString details;
-    };
-
-public:
-    explicit importSettings(QWidget *parent = 0);
-    ~importSettings();
-    
-    void loadFiles(QString path);
-    QString choosenConfig();
-
-private:
-    Ui::importSettings *ui;
-    QMap configList;
-
-private slots:
-    void updateDetails(int);
-};
-
-#endif // IMPORTSETTINGS_H
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.ui b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.ui
deleted file mode 100644
index 439c19207..000000000
--- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.ui
+++ /dev/null
@@ -1,82 +0,0 @@
-
-
- importSettings
- 
-  
-   
-    0
-    0
-    373
-    167
-   
-  
-  
-   OpenPilotGCS
-  
-  
-   
-    
-     
-      No configuration file could be found.
-Please choose from one of the default configurations
-     
-     
-      false
-     
-     
-      Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop
-     
-    
-   
-   
-    
-   
-   
-    
-     
-      TextLabel
-     
-    
-   
-   
-    
-     
-      
-       
-        Qt::Horizontal
-       
-       
-        
-         40
-         20
-        
-       
-      
-     
-     
-      
-       
-        Load
-       
-      
-     
-     
-      
-       
-        Qt::Horizontal
-       
-       
-        
-         40
-         20
-        
-       
-      
-     
-    
-   
-  
- 
- 
- 
-

From 50e66d6ee32b6833dece4a16055e6c80aa4910ed Mon Sep 17 00:00:00 2001
From: Philippe Renon 
Date: Sun, 7 Apr 2013 23:04:40 +0200
Subject: [PATCH 16/34] OP-769 initial cleanups related to language setting

---
 .../plugins/coreplugin/generalsettings.cpp    | 60 ++++++++++---------
 .../src/plugins/coreplugin/generalsettings.h  |  1 +
 2 files changed, 34 insertions(+), 27 deletions(-)

diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp
index 39a656de2..016004bc6 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp
+++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp
@@ -45,11 +45,11 @@ using namespace Core::Internal;
 
 GeneralSettings::GeneralSettings():
     m_saveSettingsOnExit(true),
-    m_dialog(0),
     m_autoConnect(true),
     m_autoSelect(true),
     m_useUDPMirror(false),
-    m_useExpertMode(false)
+    m_useExpertMode(false),
+    m_dialog(0)
 {
 }
 
@@ -88,23 +88,23 @@ void GeneralSettings::fillLanguageBox() const
     m_page->languageBox->addItem(tr(""), QString());
     // need to add this explicitly, since there is no qm file for English
     m_page->languageBox->addItem(QLatin1String("English"), QLatin1String("C"));
-    if (currentLocale == QLatin1String("C"))
+    if (currentLocale == QLatin1String("C")) {
         m_page->languageBox->setCurrentIndex(m_page->languageBox->count() - 1);
+    }
 
-    const QString creatorTrPath =
-            Core::ICore::instance()->resourcePath() + QLatin1String("/translations");
+    const QString creatorTrPath = Core::ICore::instance()->resourcePath() + QLatin1String("/translations");
     const QStringList languageFiles = QDir(creatorTrPath).entryList(QStringList(QLatin1String("openpilotgcs*.qm")));
 
-    Q_FOREACH(const QString &languageFile, languageFiles)
-    {
-        int start = languageFile.indexOf(QLatin1Char('_'))+1;
+    foreach(QString languageFile, languageFiles) {
+        int start = languageFile.indexOf(QLatin1Char('_')) + 1;
         int end = languageFile.lastIndexOf(QLatin1Char('.'));
-        const QString locale = languageFile.mid(start, end-start);
+        const QString locale = languageFile.mid(start, end - start);
         // no need to show a language that creator will not load anyway
         if (hasQmFilesForLocale(locale, creatorTrPath)) {
             m_page->languageBox->addItem(QLocale::languageToString(QLocale(locale).language()), locale);
-            if (locale == currentLocale)
+            if (locale == currentLocale) {
                 m_page->languageBox->setCurrentIndex(m_page->languageBox->count() - 1);
+            }
         }
     }
 }
@@ -114,8 +114,11 @@ QWidget *GeneralSettings::createPage(QWidget *parent)
     m_page = new Ui::GeneralSettings();
     QWidget *w = new QWidget(parent);
     m_page->setupUi(w);
+
     fillLanguageBox();
-    connect(m_page->checkAutoConnect,SIGNAL(stateChanged(int)),this,SLOT(slotAutoConnect(int)));
+
+    connect(m_page->checkAutoConnect, SIGNAL(stateChanged(int)), this, SLOT(slotAutoConnect(int)));
+
     m_page->checkBoxSaveOnExit->setChecked(m_saveSettingsOnExit);
     m_page->checkAutoConnect->setChecked(m_autoConnect);
     m_page->checkAutoSelect->setChecked(m_autoSelect);
@@ -123,8 +126,7 @@ QWidget *GeneralSettings::createPage(QWidget *parent)
     m_page->cbExpertMode->setChecked(m_useExpertMode);
     m_page->colorButton->setColor(StyleHelper::baseColor());
 
-    connect(m_page->resetButton, SIGNAL(clicked()),
-            this, SLOT(resetInterfaceColor()));
+    connect(m_page->resetButton, SIGNAL(clicked()), this, SLOT(resetInterfaceColor()));
 
     return w;
 }
@@ -148,26 +150,28 @@ void GeneralSettings::finish()
     delete m_page;
 }
 
-void GeneralSettings::readSettings(QSettings* qs)
+void GeneralSettings::readSettings(QSettings *qs)
 {
     qs->beginGroup(QLatin1String("General"));
-    m_language = qs->value(QLatin1String("OverrideLanguage"),QLocale::system().name()).toString();
-    m_saveSettingsOnExit = qs->value(QLatin1String("SaveSettingsOnExit"),m_saveSettingsOnExit).toBool();
-    m_autoConnect = qs->value(QLatin1String("AutoConnect"),m_autoConnect).toBool();
-    m_autoSelect = qs->value(QLatin1String("AutoSelect"),m_autoSelect).toBool();
-    m_useUDPMirror = qs->value(QLatin1String("UDPMirror"),m_useUDPMirror).toBool();
-    m_useExpertMode = qs->value(QLatin1String("ExpertMode"),m_useExpertMode).toBool();
+    m_language = qs->value(QLatin1String("OverrideLanguage"), QLocale::system().name()).toString();
+    m_saveSettingsOnExit = qs->value(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit).toBool();
+    m_autoConnect = qs->value(QLatin1String("AutoConnect"), m_autoConnect).toBool();
+    m_autoSelect = qs->value(QLatin1String("AutoSelect"), m_autoSelect).toBool();
+    m_useUDPMirror = qs->value(QLatin1String("UDPMirror"), m_useUDPMirror).toBool();
+    m_useExpertMode = qs->value(QLatin1String("ExpertMode"), m_useExpertMode).toBool();
     qs->endGroup();
 }
 
-void GeneralSettings::saveSettings(QSettings* qs)
+void GeneralSettings::saveSettings(QSettings *qs)
 {
     qs->beginGroup(QLatin1String("General"));
 
-    if (m_language.isEmpty())
+    if (m_language.isEmpty()) {
         qs->remove(QLatin1String("OverrideLanguage"));
-    else
+    }
+    else {
         qs->setValue(QLatin1String("OverrideLanguage"), m_language);
+    }
 
     qs->setValue(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit);
     qs->setValue(QLatin1String("AutoConnect"), m_autoConnect);
@@ -217,8 +221,8 @@ void GeneralSettings::setLanguage(const QString &locale)
 {
     if (m_language != locale) {
         if (!locale.isEmpty()) {
-        QMessageBox::information((QWidget*)Core::ICore::instance()->mainWindow(), tr("Restart required"),
-                                 tr("The language change will take effect after a restart of the OpenPilot GCS."));
+            QMessageBox::information((QWidget*) Core::ICore::instance()->mainWindow(), tr("Restart required"),
+                    tr("The language change will take effect after a restart of the OpenPilot GCS."));
         }
         m_language = locale;
     }
@@ -251,8 +255,10 @@ bool GeneralSettings::useExpertMode() const
 
 void GeneralSettings::slotAutoConnect(int value)
 {
-    if (value==Qt::Checked)
+    if (value==Qt::Checked) {
         m_page->checkAutoSelect->setEnabled(false);
-    else
+    }
+    else {
         m_page->checkAutoSelect->setEnabled(true);
+    }
 }
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h
index 8bd498fe8..dd585c304 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h
+++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h
@@ -85,6 +85,7 @@ private:
     QList m_codecs;
 
 };
+
 } // namespace Internal
 } // namespace Core
 

From 1b8c3ee7bb5152f4cc046acff2b7f06106f943d1 Mon Sep 17 00:00:00 2001
From: Oleg Semyonov 
Date: Mon, 8 Apr 2013 01:58:48 +0300
Subject: [PATCH 17/34] OP-897: fix spacing +review OPReview-438

---
 .../src/plugins/config/configinputwidget.cpp  | 32 +++++++++----------
 1 file changed, 16 insertions(+), 16 deletions(-)

diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
index 9bce4d777..67083b941 100644
--- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
@@ -125,23 +125,23 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
     connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
 
     m_config->stackedWidget->setCurrentIndex(0);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos1, 0, 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos2, 1, 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos3, 2, 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos4, 3, 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos5, 4, 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos6, 5, 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", m_config->fmsPosNum);
 
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw",1,true);
-    addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw",1,true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Roll, "Roll", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Roll, "Roll", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Roll, "Roll", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Pitch, "Pitch", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Pitch, "Pitch", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Pitch, "Pitch", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Yaw, "Yaw", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Yaw, "Yaw", 1, true);
+    addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Yaw, "Yaw", 1, true);
 
     addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
     addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);

From 2d9a2ef712637db38a694d994a21dbc8f0065d18 Mon Sep 17 00:00:00 2001
From: Oleg Semyonov 
Date: Tue, 9 Apr 2013 01:11:02 +0300
Subject: [PATCH 18/34] OP-897: fix formatting +review OPReview-438

---
 .../manualcontrolsettings.xml                 | 59 ++++++++++---------
 1 file changed, 30 insertions(+), 29 deletions(-)

diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml
index 17b85cf5f..a15b9039f 100644
--- a/shared/uavobjectdefinition/manualcontrolsettings.xml
+++ b/shared/uavobjectdefinition/manualcontrolsettings.xml
@@ -39,35 +39,36 @@
 	
         
         
-        
-        
+        
 
         
         

From 42022df009f940d97da8b2337e983494fece090d Mon Sep 17 00:00:00 2001
From: Philippe Renon 
Date: Thu, 11 Apr 2013 19:47:05 +0200
Subject: [PATCH 19/34] OP-69 allow to set language (translation) in use for
 first launch through factory defaults OP-723 do not hard code locale to en_US
 in order to allow locale specific display and entry of numbers and dates +
 revisited the GCS startup sequence

---
 ground/openpilotgcs/src/app/main.cpp | 399 ++++++++++++++++-----------
 1 file changed, 245 insertions(+), 154 deletions(-)

diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp
index 1c3e64d59..d051f06ca 100644
--- a/ground/openpilotgcs/src/app/main.cpp
+++ b/ground/openpilotgcs/src/app/main.cpp
@@ -26,6 +26,32 @@
  * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
  */
 
+/*
+ The GCS locale is set to the system locale by default unless the "hidden" setting General/Locale has a value.
+ The user can not change General/Locale from the Options dialog.
+
+ The GCS language will default to the GCS locale unless the General/OverrideLanguage has a value.
+ The user can change General/OverrideLanguage to any available language from the Options dialog.
+
+ Both General/Locale and General/OverrideLanguage can be set from the command line or through the the factory defaults file.
+
+
+
+
+ The -reset switch will clear all the user settings and will trigger a reload of the factory defaults.
+
+ You can combine it with the -configfile= command line argument to quickly switch between multiple settings files.
+
+ [code]
+ openpilotgcs -reset -configfile=./MyOpenPilotGCS.xml
+ [/code]
+
+ The specified file will be used to load the factory defaults from but only when the user settings are empty.
+ If the user settings are not empty the file will not be used.
+ This switch is useful on the 1st run when the user settings are empty or in combination with -reset.
+
+ */
+
 #include "qtsingleapplication.h"
 #include "utils/xmlconfig.h"
 #include "gcssplashscreen.h"
@@ -35,6 +61,7 @@
 #include 
 
 #include 
+#include 
 #include 
 #include 
 #include 
@@ -50,12 +77,28 @@
 #include 
 #include 
 
-#include 
+namespace {
 
-enum { OptionIndent = 4, DescriptionIndent = 24 };
+typedef QList PluginSpecSet;
+typedef QMap AppOptions;
+typedef QMap FoundAppOptions;
+
+enum {
+    OptionIndent = 4, DescriptionIndent = 24
+};
 
 static const char *appNameC = "OpenPilot GCS";
+
 static const char *corePluginNameC = "Core";
+
+#ifdef Q_OS_MAC
+static const char *SHARE_PATH = "/../Resources";
+#else
+static const char *SHARE_PATH = "/../share/openpilotgcs";
+#endif
+
+static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml";
+
 static const char *fixedOptionsC =
 " [OPTION]... [FILE]...\n"
 "Options:\n"
@@ -65,25 +108,24 @@ static const char *fixedOptionsC =
 "    -clean-config       Delete all existing configuration settings\n"
 "    -exit-after-config  Exit GCS after manipulating configuration settings\n"
 "    -D key=value        Override configuration settings e.g: -D General/OverrideLanguage=de\n"
-"    -configfile=value       Default configuration file to load if settings file is empty\n";
-static const char *HELP_OPTION1 = "-h";
-static const char *HELP_OPTION2 = "-help";
-static const char *HELP_OPTION3 = "/h";
-static const char *HELP_OPTION4 = "--help";
-static const char *VERSION_OPTION = "-version";
-static const char *CLIENT_OPTION = "-client";
-static const char *CONFIG_OPTION = "-D";
-static const char *CLEAN_CONFIG_OPTION = "-clean-config";
-static const char *EXIT_AFTER_CONFIG_OPTION = "-exit-after-config";
+"    -reset              Reset user settings to factory defaults.\n";
 
-typedef QList PluginSpecSet;
-
-static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml";
+static QLatin1String HELP_OPTION1("-h");
+static QLatin1String HELP_OPTION2("-help");
+static QLatin1String HELP_OPTION3("/h");
+static QLatin1String HELP_OPTION4("--help");
+static QLatin1String VERSION_OPTION("-version");
+static QLatin1String CLIENT_OPTION("-client");
+static QLatin1String CONFIG_OPTION("-D");
+static QLatin1String CLEAN_CONFIG_OPTION("-clean-config");
+static QLatin1String EXIT_AFTER_CONFIG_OPTION("-exit-after-config");
+static QLatin1String RESET("-reset");
+static QLatin1String NO_SPLASH("-no-splash");
 
 // Helpers for displaying messages. Note that there is no console on Windows.
 #ifdef Q_OS_WIN
 // Format as 
 HTML
-static inline void toHtml(QString &t)
+inline void toHtml(QString &t)
 {
     t.replace(QLatin1Char('&'), QLatin1String("&"));
     t.replace(QLatin1Char('<'), QLatin1String("<"));
@@ -92,58 +134,57 @@ static inline void toHtml(QString &t)
     t.append(QLatin1String("
")); } -static void displayHelpText(QString t) // No console on Windows. +void displayHelpText(QString t) // No console on Windows. { toHtml(t); QMessageBox::information(0, QLatin1String(appNameC), t); } -static void displayError(const QString &t) // No console on Windows. +void displayError(const QString &t) // No console on Windows. { QMessageBox::critical(0, QLatin1String(appNameC), t); } #else -static void displayHelpText(const QString &t) +void displayHelpText(const QString &t) { qWarning("%s", qPrintable(t)); } -static void displayError(const QString &t) +void displayError(const QString &t) { qCritical("%s", qPrintable(t)); } #endif -static void printVersion(const ExtensionSystem::PluginSpec *coreplugin, - const ExtensionSystem::PluginManager &pm) +void printVersion(const ExtensionSystem::PluginSpec *coreplugin, const ExtensionSystem::PluginManager &pm) { QString version; QTextStream str(&version); - str << '\n' << appNameC << ' ' << coreplugin->version()<< " based on Qt " << qVersion() << "\n\n"; + str << '\n' << appNameC << ' ' << coreplugin->version() << " based on Qt " << qVersion() << "\n\n"; pm.formatPluginVersions(str); str << '\n' << coreplugin->copyright() << '\n'; displayHelpText(version); } -static void printHelp(const QString &a0, const ExtensionSystem::PluginManager &pm) +void printHelp(const QString &a0, const ExtensionSystem::PluginManager &pm) { QString help; QTextStream str(&help); - str << "Usage: " << a0 << fixedOptionsC; + str << "Usage: " << a0 << fixedOptionsC; ExtensionSystem::PluginManager::formatOptions(str, OptionIndent, DescriptionIndent); - pm.formatPluginOptions(str, OptionIndent, DescriptionIndent); + pm.formatPluginOptions(str, OptionIndent, DescriptionIndent); displayHelpText(help); } -static inline QString msgCoreLoadFailure(const QString &why) +inline QString msgCoreLoadFailure(const QString &why) { return QCoreApplication::translate("Application", "Failed to load core: %1").arg(why); } -static inline QString msgSendArgumentFailed() +inline QString msgSendArgumentFailed() { return QCoreApplication::translate("Application", "Unable to send command line arguments to the already running instance. It appears to be not responding."); } @@ -151,18 +192,20 @@ static inline QString msgSendArgumentFailed() // Prepare a remote argument: If it is a relative file, add the current directory // since the the central instance might be running in a different directory. -static inline QString prepareRemoteArgument(const QString &a) +inline QString prepareRemoteArgument(const QString &a) { QFileInfo fi(a); - if (!fi.exists()) + if (!fi.exists()) { return a; - if (fi.isRelative()) + } + if (fi.isRelative()) { return fi.absoluteFilePath(); + } return a; } // Send the arguments to an already running instance of OpenPilot GCS -static bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments) +bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments) { if (!arguments.empty()) { // Send off arguments @@ -182,7 +225,21 @@ static bool sendArguments(SharedTools::QtSingleApplication &app, const QStringLi return true; } -static inline QStringList getPluginPaths() +void systemInit() +{ +#ifdef Q_OS_MAC + // increase the number of file that can be opened in OpenPilot GCS + struct rlimit rl; + getrlimit(RLIMIT_NOFILE, &rl); + rl.rlim_cur = rl.rlim_max; + setrlimit(RLIMIT_NOFILE, &rl); +#endif +#ifdef Q_OS_LINUX + QApplication::setAttribute(Qt::AA_X11InitThreads, true); +#endif +} + +inline QStringList getPluginPaths() { QStringList rc; // Figure out root: Up one from 'bin' @@ -206,22 +263,43 @@ static inline QStringList getPluginPaths() return rc; } -static void loadFactorySettings(QSettings &settings) +AppOptions options() { - QDir directory(QCoreApplication::applicationDirPath()); -#ifdef Q_OS_MAC - directory.cdUp(); - directory.cd("Resources"); -#else - directory.cdUp(); - directory.cd("share"); - directory.cd("openpilotgcs"); -#endif - directory.cd("default_configurations"); + AppOptions appOptions; + appOptions.insert(HELP_OPTION1, false); + appOptions.insert(HELP_OPTION2, false); + appOptions.insert(HELP_OPTION3, false); + appOptions.insert(HELP_OPTION4, false); + appOptions.insert(VERSION_OPTION, false); + appOptions.insert(CLIENT_OPTION, false); + appOptions.insert(CONFIG_OPTION, true); + appOptions.insert(CLEAN_CONFIG_OPTION, false); + appOptions.insert(EXIT_AFTER_CONFIG_OPTION, false); + appOptions.insert(RESET, false); + appOptions.insert(NO_SPLASH, false); + return appOptions; +} + +FoundAppOptions parseCommandLine(SharedTools::QtSingleApplication &app, ExtensionSystem::PluginManager &pluginManager, QString &errorMessage) +{ + FoundAppOptions foundAppOptions; + const QStringList arguments = app.arguments(); + if (arguments.size() > 1) { + AppOptions appOptions = options(); + if (!pluginManager.parseOptions(arguments, appOptions, &foundAppOptions, &errorMessage)) { +// displayError(errorMessage); +// printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); + } + } + return foundAppOptions; +} + +void loadFactoryDefaults(QSettings &settings) +{ + QDir directory(QCoreApplication::applicationDirPath() + QString(SHARE_PATH) + QString("/default_configurations")); qDebug() << "Looking for configuration files in:" << directory.absolutePath(); - QString filename; // check if command line contains a config file name QString commandLine; foreach(QString str, qApp->arguments()) { @@ -229,6 +307,7 @@ static void loadFactorySettings(QSettings &settings) commandLine = str.split("=").at(1); } } + QString filename; if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) { // use file name specified on command line filename = directory.absolutePath() + QDir::separator() + commandLine; @@ -244,21 +323,18 @@ static void loadFactorySettings(QSettings &settings) } // create settings from file - QSettings *qs = new QSettings(filename, XmlConfig::XmlSettingsFormat); + QSettings qs(filename, XmlConfig::XmlSettingsFormat); // transfer loaded settings to application settings - QStringList keys = qs->allKeys(); + QStringList keys = qs.allKeys(); foreach(QString key, keys) { - settings.setValue(key, qs->value(key)); + settings.setValue(key, qs.value(key)); } - // and delete loaded settings - delete qs; - qDebug() << "Configuration file" << filename << "was loaded."; } -static void overrideSettings(QSettings &settings, int argc, char **argv) +void overrideSettings(QSettings &settings, int argc, char **argv) { // Options like -DMy/setting=test QRegExp rx("([^=]+)=(.*)"); @@ -277,73 +353,24 @@ static void overrideSettings(QSettings &settings, int argc, char **argv) QList keys = settingOptions.keys(); foreach (QString key, keys) { + qDebug() << "Overriding user setting:" << key << "with value" << settingOptions.value(key); settings.setValue(key, settingOptions.value(key)); } + settings.sync(); } -#ifdef Q_OS_MAC -# define SHARE_PATH "/../Resources" -#else -# define SHARE_PATH "/../share/openpilotgcs" -#endif - -int main(int argc, char **argv) +void loadTranslators(QString language) { - QElapsedTimer timer; - timer.start(); + // TODO static!?! + static QTranslator translator; + static QTranslator qtTranslator; -#ifdef Q_OS_MAC - // increase the number of file that can be opened in OpenPilot GCS - struct rlimit rl; - getrlimit(RLIMIT_NOFILE, &rl); - rl.rlim_cur = rl.rlim_max; - setrlimit(RLIMIT_NOFILE, &rl); -#endif -#ifdef Q_OS_LINUX - QApplication::setAttribute(Qt::AA_X11InitThreads, true); -#endif - - // Set the default locale to EN, if this is not set the system locale will be used - // and as of now we dont want that behaviour. - QLocale::setDefault(QLocale::English); - - SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv); - - // Open splash screen - GCSSplashScreen splash; - splash.show(); - - // Must be done before any QSettings class is created - QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, - QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH)); - // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp - QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, QLatin1String("OpenPilot"), - QLatin1String("OpenPilotGCS_config")); - - if (!settings.allKeys().count()) { - qDebug() << "No user setting, loading factory defaults."; - // no user settings, so try to load some default ones - loadFactorySettings(settings); - } - - // override setting with command line provided settings - overrideSettings(settings, argc, argv); - - QString locale = QLocale::system().name(); - qDebug() << "main - system locale:" << locale; - - QString language = QLocale::system().name(); - language = settings.value("General/OverrideLanguage", language).toString(); - qDebug() << "main - language:" << language; - - QTranslator translator; - const QString &creatorTrPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH "/translations"); + const QString &creatorTrPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH) + QLatin1String("/translations"); if (translator.load(QLatin1String("openpilotgcs_") + language, creatorTrPath)) { const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath); const QString &qtTrFile = QLatin1String("qt_") + language; // Binary installer puts Qt tr files into creatorTrPath - QTranslator qtTranslator; if (qtTranslator.load(qtTrFile, qtTrPath) || qtTranslator.load(qtTrFile, creatorTrPath)) { QCoreApplication::installTranslator(&translator); QCoreApplication::installTranslator(&qtTranslator); @@ -352,38 +379,98 @@ int main(int argc, char **argv) translator.load(QString()); } } - app.setProperty("qtc_locale", locale); // Do we need this? +} - splash.showProgressMessage(QObject::tr("Application starting...")); +} // namespace anonymous - // Load +int main(int argc, char **argv) +{ + QElapsedTimer timer; + timer.start(); + + // low level init + systemInit(); + + // create application + SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv); + + // initialize the plugin manager ExtensionSystem::PluginManager pluginManager; pluginManager.setFileExtension(QLatin1String("pluginspec")); + pluginManager.setPluginPaths(getPluginPaths()); - const QStringList pluginPaths = getPluginPaths(); - pluginManager.setPluginPaths(pluginPaths); - - const QStringList arguments = app.arguments(); - QMap foundAppOptions; - if (arguments.size() > 1) { - QMap appOptions; - appOptions.insert(QLatin1String(HELP_OPTION1), false); - appOptions.insert(QLatin1String(HELP_OPTION2), false); - appOptions.insert(QLatin1String(HELP_OPTION3), false); - appOptions.insert(QLatin1String(HELP_OPTION4), false); - appOptions.insert(QLatin1String(VERSION_OPTION), false); - appOptions.insert(QLatin1String(CLIENT_OPTION), false); - appOptions.insert(QLatin1String(CONFIG_OPTION), true); - appOptions.insert(QLatin1String(CLEAN_CONFIG_OPTION), false); - appOptions.insert(QLatin1String(EXIT_AFTER_CONFIG_OPTION), false); - QString errorMessage; - if (!pluginManager.parseOptions(arguments, appOptions, &foundAppOptions, &errorMessage)) { - displayError(errorMessage); - printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); - return -1; - } + // parse command line + qDebug() << "Command line" << app.arguments();; + QString errorMessage; + FoundAppOptions foundAppOptions = parseCommandLine(app, pluginManager, errorMessage); + if (!errorMessage.isEmpty()) { + displayError(errorMessage); + printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); + return -1; } + // load user settings + // Must be done before any QSettings class is created + // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp + QString settingsPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH); + qDebug() << "Loading user settings from" << settingsPath; + QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, settingsPath); + QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, QLatin1String("OpenPilot"), + QLatin1String("OpenPilotGCS_config")); + + // need to reset all user settings? + if (foundAppOptions.contains(RESET)) { + qDebug() << "Resetting user settings!"; + settings.clear(); + } + + // check if we have user settings + if (!settings.allKeys().count()) { + // no user settings, load the factory defaults + qDebug() << "No user settings found, loading factory defaults..."; + loadFactoryDefaults(settings); + } + + // override settings with command line provided values + // take notice that the overridden values will be saved in the user settings and will continue to be effective + // in subsequent GCS runs + overrideSettings(settings, argc, argv); + + // initialize GCS locale + // use the value defined by the General/Locale setting or default to system locale. + // the General/Locale setting is not available in the Options dialog, it is a hidden setting but can still be changed: + // - through the command line + // - editing the factory defaults XML file before 1st launch + // - editing the user XML file + QString localeName = settings.value("General/Locale", QLocale::system().name()).toString(); + QLocale::setDefault(localeName); + + // some debuging + qDebug() << "main - system locale:" << QLocale::system().name(); + qDebug() << "main - GCS locale:" << QLocale().name(); + + // load translation file + // the language used is defined by the General/OverrideLanguage setting (defaults to GCS locale) + // if the translation file for the given language is not found, GCS will default to built in English. + QString language = settings.value("General/OverrideLanguage", localeName).toString(); + qDebug() << "main - translation language:" << language; + loadTranslators(language); + + app.setProperty("qtc_locale", localeName); // Do we need this? + + // open the splash screen + GCSSplashScreen *splash = 0; + if (!foundAppOptions.contains(NO_SPLASH)) { + splash = new GCSSplashScreen(); + // show splash + splash->showProgressMessage(QObject::tr("Application starting...")); + splash->show(); + // connect to track progress of plugin manager + QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)), + splash, SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*))); + } + + // find and load core plugin const PluginSpecSet plugins = pluginManager.plugins(); ExtensionSystem::PluginSpec *coreplugin = 0; foreach (ExtensionSystem::PluginSpec *spec, plugins) { @@ -393,7 +480,7 @@ int main(int argc, char **argv) } } if (!coreplugin) { - QString nativePaths = QDir::toNativeSeparators(pluginPaths.join(QLatin1String(","))); + QString nativePaths = QDir::toNativeSeparators(getPluginPaths().join(QLatin1String(","))); const QString reason = QCoreApplication::translate("Application", "Could not find 'Core.pluginspec' in %1").arg( nativePaths); displayError(msgCoreLoadFailure(reason)); @@ -403,28 +490,27 @@ int main(int argc, char **argv) displayError(msgCoreLoadFailure(coreplugin->errorString())); return 1; } - if (foundAppOptions.contains(QLatin1String(VERSION_OPTION))) { + + if (foundAppOptions.contains(VERSION_OPTION)) { printVersion(coreplugin, pluginManager); return 0; } - if (foundAppOptions.contains(QLatin1String(EXIT_AFTER_CONFIG_OPTION))) { + if (foundAppOptions.contains(EXIT_AFTER_CONFIG_OPTION)) { return 0; } - if (foundAppOptions.contains(QLatin1String(HELP_OPTION1)) - || foundAppOptions.contains(QLatin1String(HELP_OPTION2)) - || foundAppOptions.contains(QLatin1String(HELP_OPTION3)) - || foundAppOptions.contains(QLatin1String(HELP_OPTION4))) { + if (foundAppOptions.contains(HELP_OPTION1) + || foundAppOptions.contains(HELP_OPTION2) + || foundAppOptions.contains(HELP_OPTION3) + || foundAppOptions.contains(HELP_OPTION4)) { printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); return 0; } + const bool isFirstInstance = !app.isRunning(); - if (!isFirstInstance && foundAppOptions.contains(QLatin1String(CLIENT_OPTION))) { + if (!isFirstInstance && foundAppOptions.contains(CLIENT_OPTION)) { return sendArguments(app, pluginManager.arguments()) ? 0 : -1; } - QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)), - &splash, SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*))); - pluginManager.loadPlugins(); if (coreplugin->hasError()) { @@ -434,19 +520,21 @@ int main(int argc, char **argv) { QStringList errors; - foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) - if (p->hasError()) + foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) { + if (p->hasError()) { errors.append(p->errorString()); - if (!errors.isEmpty()) + } + } + if (!errors.isEmpty()) { QMessageBox::warning(0, - QCoreApplication::translate("Application", "OpenPilot GCS - Plugin loader messages"), - errors.join(QString::fromLatin1("\n\n"))); + QCoreApplication::translate("Application", "OpenPilot GCS - Plugin loader messages"), + errors.join(QString::fromLatin1("\n\n"))); + } } if (isFirstInstance) { // Set up lock and remote arguments for the first instance only. - // Silently fallback to unconnected instances for any subsequent - // instances. + // Silently fallback to unconnected instances for any subsequent instances. app.initialize(); QObject::connect(&app, SIGNAL(messageReceived(QString)), coreplugin->plugin(), SLOT(remoteArgument(QString))); } @@ -455,9 +543,12 @@ int main(int argc, char **argv) // Do this after the event loop has started QTimer::singleShot(100, &pluginManager, SLOT(startTests())); - //Update message and postpone closing of splashscreen 3 seconds - splash.showProgressMessage(QObject::tr("Application started.")); - QTimer::singleShot(1500, &splash, SLOT(close())); + if (splash) { + // Update message and postpone closing of splashscreen 3 seconds + splash->showProgressMessage(QObject::tr("Application started.")); + QTimer::singleShot(1500, splash, SLOT(close())); + // TODO delete splash + } qDebug() << "main - main took" << timer.elapsed() << "ms"; From 3c3080a441d85ed1051da3c68632a395428a8c42 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 13 Apr 2013 14:49:11 +0200 Subject: [PATCH 20/34] OP-769 OP-723 GCS main cleanups as per OPReview-440 + documented new -no-splash switch --- ground/openpilotgcs/src/app/main.cpp | 517 ++++++++++++++------------- 1 file changed, 259 insertions(+), 258 deletions(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index d051f06ca..84c25f522 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -79,307 +79,305 @@ namespace { -typedef QList PluginSpecSet; -typedef QMap AppOptions; -typedef QMap FoundAppOptions; + typedef QList PluginSpecSet; + typedef QMap AppOptions; + typedef QMap FoundAppOptions; -enum { - OptionIndent = 4, DescriptionIndent = 24 -}; + enum { + OptionIndent = 4, DescriptionIndent = 24 + }; -static const char *appNameC = "OpenPilot GCS"; + const char *appNameC = "OpenPilot GCS"; -static const char *corePluginNameC = "Core"; + const char *corePluginNameC = "Core"; #ifdef Q_OS_MAC -static const char *SHARE_PATH = "/../Resources"; + const char *SHARE_PATH = "/../Resources"; #else -static const char *SHARE_PATH = "/../share/openpilotgcs"; + const char *SHARE_PATH = "/../share/openpilotgcs"; #endif -static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml"; + const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml"; -static const char *fixedOptionsC = -" [OPTION]... [FILE]...\n" -"Options:\n" -" -help Display this help\n" -" -version Display program version\n" -" -client Attempt to connect to already running instance\n" -" -clean-config Delete all existing configuration settings\n" -" -exit-after-config Exit GCS after manipulating configuration settings\n" -" -D key=value Override configuration settings e.g: -D General/OverrideLanguage=de\n" -" -reset Reset user settings to factory defaults.\n"; + const char *fixedOptionsC = + " [OPTION]... [FILE]...\n" + "Options:\n" + " -help Display this help\n" + " -version Display program version\n" + " -no-splash Don't display splash screen\n" + " -client Attempt to connect to already running instance\n" + " -clean-config Delete all existing configuration settings\n" + " -exit-after-config Exit GCS after manipulating configuration settings\n" + " -D key=value Override configuration settings e.g: -D General/OverrideLanguage=de\n" + " -reset Reset user settings to factory defaults.\n"; -static QLatin1String HELP_OPTION1("-h"); -static QLatin1String HELP_OPTION2("-help"); -static QLatin1String HELP_OPTION3("/h"); -static QLatin1String HELP_OPTION4("--help"); -static QLatin1String VERSION_OPTION("-version"); -static QLatin1String CLIENT_OPTION("-client"); -static QLatin1String CONFIG_OPTION("-D"); -static QLatin1String CLEAN_CONFIG_OPTION("-clean-config"); -static QLatin1String EXIT_AFTER_CONFIG_OPTION("-exit-after-config"); -static QLatin1String RESET("-reset"); -static QLatin1String NO_SPLASH("-no-splash"); + const QLatin1String HELP_OPTION1("-h"); + const QLatin1String HELP_OPTION2("-help"); + const QLatin1String HELP_OPTION3("/h"); + const QLatin1String HELP_OPTION4("--help"); + const QLatin1String VERSION_OPTION("-version"); + const QLatin1String CLIENT_OPTION("-client"); + const QLatin1String CONFIG_OPTION("-D"); + const QLatin1String CLEAN_CONFIG_OPTION("-clean-config"); + const QLatin1String EXIT_AFTER_CONFIG_OPTION("-exit-after-config"); + const QLatin1String RESET("-reset"); + const QLatin1String NO_SPLASH("-no-splash"); -// Helpers for displaying messages. Note that there is no console on Windows. + // Helpers for displaying messages. Note that there is no console on Windows. #ifdef Q_OS_WIN -// Format as
 HTML
-inline void toHtml(QString &t)
-{
-    t.replace(QLatin1Char('&'), QLatin1String("&"));
-    t.replace(QLatin1Char('<'), QLatin1String("<"));
-    t.replace(QLatin1Char('>'), QLatin1String(">"));
-    t.insert(0, QLatin1String("
"));
-    t.append(QLatin1String("
")); -} -void displayHelpText(QString t) // No console on Windows. -{ - toHtml(t); - QMessageBox::information(0, QLatin1String(appNameC), t); -} + // Format as
 HTML
+    inline void toHtml(QString &t)
+    {
+        t.replace(QLatin1Char('&'), QLatin1String("&"));
+        t.replace(QLatin1Char('<'), QLatin1String("<"));
+        t.replace(QLatin1Char('>'), QLatin1String(">"));
+        t.insert(0, QLatin1String("
"));
+        t.append(QLatin1String("
")); + } -void displayError(const QString &t) // No console on Windows. -{ - QMessageBox::critical(0, QLatin1String(appNameC), t); -} + void displayHelpText(QString t) // No console on Windows. + { + toHtml(t); + QMessageBox::information(0, QLatin1String(appNameC), t); + } + + void displayError(const QString &t) // No console on Windows. + { + QMessageBox::critical(0, QLatin1String(appNameC), t); + } #else -void displayHelpText(const QString &t) -{ - qWarning("%s", qPrintable(t)); -} + void displayHelpText(const QString &t) + { + qWarning("%s", qPrintable(t)); + } -void displayError(const QString &t) -{ - qCritical("%s", qPrintable(t)); -} + void displayError(const QString &t) + { + qCritical("%s", qPrintable(t)); + } #endif -void printVersion(const ExtensionSystem::PluginSpec *coreplugin, const ExtensionSystem::PluginManager &pm) -{ - QString version; - QTextStream str(&version); - str << '\n' << appNameC << ' ' << coreplugin->version() << " based on Qt " << qVersion() << "\n\n"; - pm.formatPluginVersions(str); - str << '\n' << coreplugin->copyright() << '\n'; - displayHelpText(version); -} + void printVersion(const ExtensionSystem::PluginSpec *coreplugin, const ExtensionSystem::PluginManager &pm) + { + QString version; + QTextStream str(&version); + str << '\n' << appNameC << ' ' << coreplugin->version() << " based on Qt " << qVersion() << "\n\n"; + pm.formatPluginVersions(str); + str << '\n' << coreplugin->copyright() << '\n'; + displayHelpText(version); + } -void printHelp(const QString &a0, const ExtensionSystem::PluginManager &pm) -{ - QString help; - QTextStream str(&help); - str << "Usage: " << a0 << fixedOptionsC; - ExtensionSystem::PluginManager::formatOptions(str, OptionIndent, DescriptionIndent); - pm.formatPluginOptions(str, OptionIndent, DescriptionIndent); - displayHelpText(help); -} + void printHelp(const QString &a0, const ExtensionSystem::PluginManager &pm) + { + QString help; + QTextStream str(&help); + str << "Usage: " << a0 << fixedOptionsC; + ExtensionSystem::PluginManager::formatOptions(str, OptionIndent, DescriptionIndent); + pm.formatPluginOptions(str, OptionIndent, DescriptionIndent); + displayHelpText(help); + } -inline QString msgCoreLoadFailure(const QString &why) -{ - return QCoreApplication::translate("Application", "Failed to load core: %1").arg(why); -} + inline QString msgCoreLoadFailure(const QString &why) + { + return QCoreApplication::translate("Application", "Failed to load core: %1").arg(why); + } -inline QString msgSendArgumentFailed() -{ - return QCoreApplication::translate("Application", "Unable to send command line arguments to the already running instance. It appears to be not responding."); -} + inline QString msgSendArgumentFailed() + { + return QCoreApplication::translate("Application", "Unable to send command line arguments to the already running instance. It appears to be not responding."); + } -// Prepare a remote argument: If it is a relative file, add the current directory -// since the the central instance might be running in a different directory. + // Prepare a remote argument: If it is a relative file, add the current directory + // since the the central instance might be running in a different directory. -inline QString prepareRemoteArgument(const QString &a) -{ - QFileInfo fi(a); - if (!fi.exists()) { + inline QString prepareRemoteArgument(const QString &a) + { + QFileInfo fi(a); + if (!fi.exists()) { + return a; + } + if (fi.isRelative()) { + return fi.absoluteFilePath(); + } return a; } - if (fi.isRelative()) { - return fi.absoluteFilePath(); - } - return a; -} -// Send the arguments to an already running instance of OpenPilot GCS -bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments) -{ - if (!arguments.empty()) { - // Send off arguments - const QStringList::const_iterator acend = arguments.constEnd(); - for (QStringList::const_iterator it = arguments.constBegin(); it != acend; ++it) { - if (!app.sendMessage(prepareRemoteArgument(*it))) { - displayError(msgSendArgumentFailed()); - return false; + // Send the arguments to an already running instance of OpenPilot GCS + bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments) + { + if (!arguments.empty()) { + // Send off arguments + const QStringList::const_iterator acend = arguments.constEnd(); + for (QStringList::const_iterator it = arguments.constBegin(); it != acend; ++it) { + if (!app.sendMessage(prepareRemoteArgument(*it))) { + displayError(msgSendArgumentFailed()); + return false; + } } } + // Special empty argument means: Show and raise (the slot just needs to be triggered) + if (!app.sendMessage(QString())) { + displayError(msgSendArgumentFailed()); + return false; + } + return true; } - // Special empty argument means: Show and raise (the slot just needs to be triggered) - if (!app.sendMessage(QString())) { - displayError(msgSendArgumentFailed()); - return false; - } - return true; -} -void systemInit() -{ + void systemInit() + { #ifdef Q_OS_MAC - // increase the number of file that can be opened in OpenPilot GCS - struct rlimit rl; - getrlimit(RLIMIT_NOFILE, &rl); - rl.rlim_cur = rl.rlim_max; - setrlimit(RLIMIT_NOFILE, &rl); + // increase the number of file that can be opened in OpenPilot GCS + struct rlimit rl; + getrlimit(RLIMIT_NOFILE, &rl); + rl.rlim_cur = rl.rlim_max; + setrlimit(RLIMIT_NOFILE, &rl); #endif #ifdef Q_OS_LINUX - QApplication::setAttribute(Qt::AA_X11InitThreads, true); + QApplication::setAttribute(Qt::AA_X11InitThreads, true); #endif -} - -inline QStringList getPluginPaths() -{ - QStringList rc; - // Figure out root: Up one from 'bin' - QDir rootDir = QApplication::applicationDirPath(); - rootDir.cdUp(); - const QString rootDirPath = rootDir.canonicalPath(); - // 1) "plugins" (Win/Linux) - QString pluginPath = rootDirPath; - pluginPath += QLatin1Char('/'); - pluginPath += QLatin1String(GCS_LIBRARY_BASENAME); - pluginPath += QLatin1Char('/'); - pluginPath += QLatin1String("openpilotgcs"); - pluginPath += QLatin1Char('/'); - pluginPath += QLatin1String("plugins"); - rc.push_back(pluginPath); - // 2) "PlugIns" (OS X) - pluginPath = rootDirPath; - pluginPath += QLatin1Char('/'); - pluginPath += QLatin1String("Plugins"); - rc.push_back(pluginPath); - return rc; -} - -AppOptions options() -{ - AppOptions appOptions; - appOptions.insert(HELP_OPTION1, false); - appOptions.insert(HELP_OPTION2, false); - appOptions.insert(HELP_OPTION3, false); - appOptions.insert(HELP_OPTION4, false); - appOptions.insert(VERSION_OPTION, false); - appOptions.insert(CLIENT_OPTION, false); - appOptions.insert(CONFIG_OPTION, true); - appOptions.insert(CLEAN_CONFIG_OPTION, false); - appOptions.insert(EXIT_AFTER_CONFIG_OPTION, false); - appOptions.insert(RESET, false); - appOptions.insert(NO_SPLASH, false); - return appOptions; -} - -FoundAppOptions parseCommandLine(SharedTools::QtSingleApplication &app, ExtensionSystem::PluginManager &pluginManager, QString &errorMessage) -{ - FoundAppOptions foundAppOptions; - const QStringList arguments = app.arguments(); - if (arguments.size() > 1) { - AppOptions appOptions = options(); - if (!pluginManager.parseOptions(arguments, appOptions, &foundAppOptions, &errorMessage)) { -// displayError(errorMessage); -// printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); - } - } - return foundAppOptions; -} - -void loadFactoryDefaults(QSettings &settings) -{ - QDir directory(QCoreApplication::applicationDirPath() + QString(SHARE_PATH) + QString("/default_configurations")); - - qDebug() << "Looking for configuration files in:" << directory.absolutePath(); - - // check if command line contains a config file name - QString commandLine; - foreach(QString str, qApp->arguments()) { - if (str.contains("configfile")) { - commandLine = str.split("=").at(1); - } - } - QString filename; - if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) { - // use file name specified on command line - filename = directory.absolutePath() + QDir::separator() + commandLine; - qDebug() << "Configuration file" << filename << "specified on command line will be loaded."; - } else if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) { - // use default file name - filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME; - qDebug() << "Default configuration file" << filename << "will be loaded."; - } else { - // TODO should we exit violently? - qWarning() << "No default configuration file found!"; - return; } - // create settings from file - QSettings qs(filename, XmlConfig::XmlSettingsFormat); - - // transfer loaded settings to application settings - QStringList keys = qs.allKeys(); - foreach(QString key, keys) { - settings.setValue(key, qs.value(key)); + inline QStringList getPluginPaths() + { + QStringList rc; + // Figure out root: Up one from 'bin' + QDir rootDir = QApplication::applicationDirPath(); + rootDir.cdUp(); + const QString rootDirPath = rootDir.canonicalPath(); + // 1) "plugins" (Win/Linux) + QString pluginPath = rootDirPath; + pluginPath += QLatin1Char('/'); + pluginPath += QLatin1String(GCS_LIBRARY_BASENAME); + pluginPath += QLatin1Char('/'); + pluginPath += QLatin1String("openpilotgcs"); + pluginPath += QLatin1Char('/'); + pluginPath += QLatin1String("plugins"); + rc.push_back(pluginPath); + // 2) "PlugIns" (OS X) + pluginPath = rootDirPath; + pluginPath += QLatin1Char('/'); + pluginPath += QLatin1String("Plugins"); + rc.push_back(pluginPath); + return rc; } - qDebug() << "Configuration file" << filename << "was loaded."; -} + AppOptions options() + { + AppOptions appOptions; + appOptions.insert(HELP_OPTION1, false); + appOptions.insert(HELP_OPTION2, false); + appOptions.insert(HELP_OPTION3, false); + appOptions.insert(HELP_OPTION4, false); + appOptions.insert(VERSION_OPTION, false); + appOptions.insert(CLIENT_OPTION, false); + appOptions.insert(CONFIG_OPTION, true); + appOptions.insert(CLEAN_CONFIG_OPTION, false); + appOptions.insert(EXIT_AFTER_CONFIG_OPTION, false); + appOptions.insert(RESET, false); + appOptions.insert(NO_SPLASH, false); + return appOptions; + } -void overrideSettings(QSettings &settings, int argc, char **argv) -{ - // Options like -DMy/setting=test - QRegExp rx("([^=]+)=(.*)"); - - QMap settingOptions; - for (int i = 0; i < argc; ++i) { - if (QString(CONFIG_OPTION).compare(QString(argv[i])) == 0) { - if (rx.indexIn(argv[++i]) > -1) { - settingOptions.insert(rx.cap(1), rx.cap(2)); + FoundAppOptions parseCommandLine(SharedTools::QtSingleApplication &app, ExtensionSystem::PluginManager &pluginManager, QString &errorMessage) + { + FoundAppOptions foundAppOptions; + const QStringList arguments = app.arguments(); + if (arguments.size() > 1) { + AppOptions appOptions = options(); + if (!pluginManager.parseOptions(arguments, appOptions, &foundAppOptions, &errorMessage)) { + // displayError(errorMessage); + // printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); } } - if (QString(CLEAN_CONFIG_OPTION).compare(QString(argv[i])) == 0) { - settings.clear(); + return foundAppOptions; + } + + void loadFactoryDefaults(QSettings &settings) + { + QDir directory(QCoreApplication::applicationDirPath() + QString(SHARE_PATH) + QString("/default_configurations")); + + qDebug() << "Looking for configuration files in:" << directory.absolutePath(); + + // check if command line contains a config file name + QString commandLine; + foreach(QString str, qApp->arguments()) { + if (str.contains("configfile")) { + commandLine = str.split("=").at(1); + } } - } - - QList keys = settingOptions.keys(); - foreach (QString key, keys) { - qDebug() << "Overriding user setting:" << key << "with value" << settingOptions.value(key); - settings.setValue(key, settingOptions.value(key)); - } - - settings.sync(); -} - -void loadTranslators(QString language) -{ - // TODO static!?! - static QTranslator translator; - static QTranslator qtTranslator; - - const QString &creatorTrPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH) + QLatin1String("/translations"); - if (translator.load(QLatin1String("openpilotgcs_") + language, creatorTrPath)) { - const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath); - const QString &qtTrFile = QLatin1String("qt_") + language; - // Binary installer puts Qt tr files into creatorTrPath - if (qtTranslator.load(qtTrFile, qtTrPath) || qtTranslator.load(qtTrFile, creatorTrPath)) { - QCoreApplication::installTranslator(&translator); - QCoreApplication::installTranslator(&qtTranslator); + QString filename; + if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) { + // use file name specified on command line + filename = directory.absolutePath() + QDir::separator() + commandLine; + qDebug() << "Configuration file" << filename << "specified on command line will be loaded."; + } else if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) { + // use default file name + filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME; + qDebug() << "Default configuration file" << filename << "will be loaded."; } else { - // unload() - translator.load(QString()); + // TODO should we exit violently? + qWarning() << "No default configuration file found!"; + return; + } + + // create settings from file + QSettings qs(filename, XmlConfig::XmlSettingsFormat); + + // transfer loaded settings to application settings + QStringList keys = qs.allKeys(); + foreach(QString key, keys) { + settings.setValue(key, qs.value(key)); + } + + qDebug() << "Configuration file" << filename << "was loaded."; + } + + void overrideSettings(QSettings &settings, int argc, char **argv) + { + // Options like -DMy/setting=test + QRegExp rx("([^=]+)=(.*)"); + + QMap settingOptions; + for (int i = 0; i < argc; ++i) { + if (QString(CONFIG_OPTION).compare(QString(argv[i])) == 0) { + if (rx.indexIn(argv[++i]) > -1) { + settingOptions.insert(rx.cap(1), rx.cap(2)); + } + } + if (QString(CLEAN_CONFIG_OPTION).compare(QString(argv[i])) == 0) { + settings.clear(); + } + } + + QList keys = settingOptions.keys(); + foreach (QString key, keys) { + qDebug() << "Overriding user setting:" << key << "with value" << settingOptions.value(key); + settings.setValue(key, settingOptions.value(key)); + } + + settings.sync(); + } + + void loadTranslators(QString language, QTranslator &translator, QTranslator &qtTranslator) + { + const QString &creatorTrPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH) + QLatin1String("/translations"); + if (translator.load(QLatin1String("openpilotgcs_") + language, creatorTrPath)) { + const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath); + const QString &qtTrFile = QLatin1String("qt_") + language; + // Binary installer puts Qt tr files into creatorTrPath + if (qtTranslator.load(qtTrFile, qtTrPath) || qtTranslator.load(qtTrFile, creatorTrPath)) { + QCoreApplication::installTranslator(&translator); + QCoreApplication::installTranslator(&qtTranslator); + } else { + // unload() + translator.load(QString()); + } } } -} } // namespace anonymous @@ -404,6 +402,8 @@ int main(int argc, char **argv) QString errorMessage; FoundAppOptions foundAppOptions = parseCommandLine(app, pluginManager, errorMessage); if (!errorMessage.isEmpty()) { + // this will display two popups : one error popup + one usage string popup + // TODO merge two popups into one. displayError(errorMessage); printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); return -1; @@ -454,7 +454,9 @@ int main(int argc, char **argv) // if the translation file for the given language is not found, GCS will default to built in English. QString language = settings.value("General/OverrideLanguage", localeName).toString(); qDebug() << "main - translation language:" << language; - loadTranslators(language); + QTranslator translator; + QTranslator qtTranslator; + loadTranslators(language, translator, qtTranslator); app.setProperty("qtc_locale", localeName); // Do we need this? @@ -544,10 +546,9 @@ int main(int argc, char **argv) QTimer::singleShot(100, &pluginManager, SLOT(startTests())); if (splash) { - // Update message and postpone closing of splashscreen 3 seconds - splash->showProgressMessage(QObject::tr("Application started.")); - QTimer::singleShot(1500, splash, SLOT(close())); - // TODO delete splash + // close and delete splash + splash->close(); + delete splash; } qDebug() << "main - main took" << timer.elapsed() << "ms"; From 208e97f476f70a6069ef7c811f7cca62bfa759fd Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Thu, 18 Apr 2013 01:28:11 +0200 Subject: [PATCH 21/34] OP-769 cleaned up handling of options in main + other cleanups --- ground/openpilotgcs/src/app/main.cpp | 250 +++++++++++++++------------ 1 file changed, 142 insertions(+), 108 deletions(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index 84c25f522..4db9e429a 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -35,21 +35,46 @@ Both General/Locale and General/OverrideLanguage can be set from the command line or through the the factory defaults file. - - + The -D option is used to permanently set a user setting. The -reset switch will clear all the user settings and will trigger a reload of the factory defaults. You can combine it with the -configfile= command line argument to quickly switch between multiple settings files. [code] - openpilotgcs -reset -configfile=./MyOpenPilotGCS.xml + openpilotgcs -reset -config-file ./MyOpenPilotGCS.xml [/code] + Relative paths are relative to /share/openpilotgcs/default_configurations/ + The specified file will be used to load the factory defaults from but only when the user settings are empty. If the user settings are not empty the file will not be used. This switch is useful on the 1st run when the user settings are empty or in combination with -reset. + + Quickly switch configurations + + [code] + -reset -config-file + [/code] + + Configuring GCS from installer + + The -D option is used to permanently set a user setting. + + If the user chooses to start GCS at the end of the installer: + + [code] + -D General/OverrideLanguage=de + [/code] + + If the user chooses not to start GCS at the end of the installer, you still need to configure GCS. + In that case you can use -exit-after-config + + [code] + -D General/OverrideLanguage=de -exit-after-config + [/code] + */ #include "qtsingleapplication.h" @@ -81,47 +106,49 @@ namespace { typedef QList PluginSpecSet; typedef QMap AppOptions; - typedef QMap FoundAppOptions; + typedef QMap AppOptionValues; enum { OptionIndent = 4, DescriptionIndent = 24 }; - const char *appNameC = "OpenPilot GCS"; + const QLatin1String APP_NAME("OpenPilot GCS"); - const char *corePluginNameC = "Core"; + const QLatin1String CORE_PLUGIN_NAME("Core"); + + const QLatin1String SETTINGS_ORG_NAME("OpenPilot"); + const QLatin1String SETTINGS_APP_NAME("OpenPilotGCS_config"); #ifdef Q_OS_MAC - const char *SHARE_PATH = "/../Resources"; + const QLatin1String SHARE_PATH("/../Resources"); #else - const char *SHARE_PATH = "/../share/openpilotgcs"; + const QLatin1String SHARE_PATH("/../share/openpilotgcs"); #endif const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml"; - const char *fixedOptionsC = - " [OPTION]... [FILE]...\n" - "Options:\n" - " -help Display this help\n" - " -version Display program version\n" - " -no-splash Don't display splash screen\n" - " -client Attempt to connect to already running instance\n" - " -clean-config Delete all existing configuration settings\n" - " -exit-after-config Exit GCS after manipulating configuration settings\n" - " -D key=value Override configuration settings e.g: -D General/OverrideLanguage=de\n" - " -reset Reset user settings to factory defaults.\n"; + const char *fixedOptionsC = " [OPTION]... [FILE]...\n" + "Options:\n" + " -help Display this help\n" + " -version Display application version\n" + " -no-splash Don't display splash screen\n" + " -client Attempt to connect to already running instance\n" + " -D = Permanently set a user setting, e.g: -D General/OverrideLanguage=de\n" + " -reset Reset user settings to factory defaults.\n" + " -config-file Specify alternate factory defaults settings file (used with -reset)\n" + " -exit-after-config Exit after manipulating configuration settings\n"; - const QLatin1String HELP_OPTION1("-h"); - const QLatin1String HELP_OPTION2("-help"); - const QLatin1String HELP_OPTION3("/h"); - const QLatin1String HELP_OPTION4("--help"); + const QLatin1String HELP1_OPTION("-h"); + const QLatin1String HELP2_OPTION("-help"); + const QLatin1String HELP3_OPTION("/h"); + const QLatin1String HELP4_OPTION("--help"); const QLatin1String VERSION_OPTION("-version"); + const QLatin1String NO_SPLASH_OPTION("-no-splash"); const QLatin1String CLIENT_OPTION("-client"); const QLatin1String CONFIG_OPTION("-D"); - const QLatin1String CLEAN_CONFIG_OPTION("-clean-config"); + const QLatin1String RESET_OPTION("-reset"); + const QLatin1String CONFIG_FILE_OPTION("-config-file"); const QLatin1String EXIT_AFTER_CONFIG_OPTION("-exit-after-config"); - const QLatin1String RESET("-reset"); - const QLatin1String NO_SPLASH("-no-splash"); // Helpers for displaying messages. Note that there is no console on Windows. #ifdef Q_OS_WIN @@ -139,12 +166,12 @@ namespace { void displayHelpText(QString t) // No console on Windows. { toHtml(t); - QMessageBox::information(0, QLatin1String(appNameC), t); + QMessageBox::information(0, APP_NAME, t); } void displayError(const QString &t) // No console on Windows. { - QMessageBox::critical(0, QLatin1String(appNameC), t); + QMessageBox::critical(0, APP_NAME, t); } #else @@ -165,7 +192,7 @@ namespace { { QString version; QTextStream str(&version); - str << '\n' << appNameC << ' ' << coreplugin->version() << " based on Qt " << qVersion() << "\n\n"; + str << '\n' << APP_NAME << ' ' << coreplugin->version() << " based on Qt " << qVersion() << "\n\n"; pm.formatPluginVersions(str); str << '\n' << coreplugin->copyright() << '\n'; displayHelpText(version); @@ -188,12 +215,12 @@ namespace { inline QString msgSendArgumentFailed() { - return QCoreApplication::translate("Application", "Unable to send command line arguments to the already running instance. It appears to be not responding."); + return QCoreApplication::translate("Application", + "Unable to send command line arguments to the already running instance. It appears to be not responding."); } // Prepare a remote argument: If it is a relative file, add the current directory // since the the central instance might be running in a different directory. - inline QString prepareRemoteArgument(const QString &a) { QFileInfo fi(a); @@ -206,7 +233,7 @@ namespace { return a; } - // Send the arguments to an already running instance of OpenPilot GCS + // Send the arguments to an already running instance of application bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments) { if (!arguments.empty()) { @@ -230,7 +257,7 @@ namespace { void systemInit() { #ifdef Q_OS_MAC - // increase the number of file that can be opened in OpenPilot GCS + // increase the number of file that can be opened in application struct rlimit rl; getrlimit(RLIMIT_NOFILE, &rl); rl.rlim_cur = rl.rlim_max; @@ -268,95 +295,99 @@ namespace { AppOptions options() { AppOptions appOptions; - appOptions.insert(HELP_OPTION1, false); - appOptions.insert(HELP_OPTION2, false); - appOptions.insert(HELP_OPTION3, false); - appOptions.insert(HELP_OPTION4, false); + appOptions.insert(HELP1_OPTION, false); + appOptions.insert(HELP2_OPTION, false); + appOptions.insert(HELP3_OPTION, false); + appOptions.insert(HELP4_OPTION, false); appOptions.insert(VERSION_OPTION, false); + appOptions.insert(NO_SPLASH_OPTION, false); appOptions.insert(CLIENT_OPTION, false); appOptions.insert(CONFIG_OPTION, true); - appOptions.insert(CLEAN_CONFIG_OPTION, false); + appOptions.insert(RESET_OPTION, false); + appOptions.insert(CONFIG_FILE_OPTION, true); appOptions.insert(EXIT_AFTER_CONFIG_OPTION, false); - appOptions.insert(RESET, false); - appOptions.insert(NO_SPLASH, false); return appOptions; } - FoundAppOptions parseCommandLine(SharedTools::QtSingleApplication &app, ExtensionSystem::PluginManager &pluginManager, QString &errorMessage) + AppOptionValues parseCommandLine(SharedTools::QtSingleApplication &app, + ExtensionSystem::PluginManager &pluginManager, QString &errorMessage) { - FoundAppOptions foundAppOptions; + AppOptionValues appOptionValues; const QStringList arguments = app.arguments(); if (arguments.size() > 1) { AppOptions appOptions = options(); - if (!pluginManager.parseOptions(arguments, appOptions, &foundAppOptions, &errorMessage)) { - // displayError(errorMessage); - // printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); - } + pluginManager.parseOptions(arguments, appOptions, &appOptionValues, &errorMessage); } - return foundAppOptions; + return appOptionValues; } - void loadFactoryDefaults(QSettings &settings) + void loadFactoryDefaults(QSettings &settings, AppOptionValues &appOptionValues) { - QDir directory(QCoreApplication::applicationDirPath() + QString(SHARE_PATH) + QString("/default_configurations")); + QDir directory(QCoreApplication::applicationDirPath() + SHARE_PATH + QString("/default_configurations")); + qDebug() << "Looking for factory defaults configuration files in:" << directory.absolutePath(); - qDebug() << "Looking for configuration files in:" << directory.absolutePath(); + QString fileName; - // check if command line contains a config file name - QString commandLine; - foreach(QString str, qApp->arguments()) { - if (str.contains("configfile")) { - commandLine = str.split("=").at(1); + // check if command line option -config-file contains a file name + QString commandLine = appOptionValues.value(CONFIG_FILE_OPTION); + if (!commandLine.isEmpty()) { + if (QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) { + // file name specified on command line has a relative path + fileName = directory.absolutePath() + QDir::separator() + commandLine; + qDebug() << "Configuration file" << fileName << "specified on command line will be loaded."; + } else if (QFile::exists(commandLine)) { + // file name specified on command line has an absolutee path + fileName = commandLine; + qDebug() << "Configuration file" << fileName << "specified on command line will be loaded."; + } else { + qWarning() << "Configuration file" << commandLine << "specified on command line does not exist."; } } - QString filename; - if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) { - // use file name specified on command line - filename = directory.absolutePath() + QDir::separator() + commandLine; - qDebug() << "Configuration file" << filename << "specified on command line will be loaded."; - } else if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) { - // use default file name - filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME; - qDebug() << "Default configuration file" << filename << "will be loaded."; - } else { + + if (fileName.isEmpty()) { + // check default file + if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) { + // use default file name + fileName = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME; + qDebug() << "Default configuration file" << fileName << "will be loaded."; + } else { + qWarning() << "No default configuration file found in" << directory.absolutePath(); + } + } + + if (fileName.isEmpty()) { // TODO should we exit violently? - qWarning() << "No default configuration file found!"; + qCritical() << "No default configuration file found!"; return; } // create settings from file - QSettings qs(filename, XmlConfig::XmlSettingsFormat); + QSettings qs(fileName, XmlConfig::XmlSettingsFormat); // transfer loaded settings to application settings QStringList keys = qs.allKeys(); - foreach(QString key, keys) { + foreach(QString key, keys) + { settings.setValue(key, qs.value(key)); } - qDebug() << "Configuration file" << filename << "was loaded."; + qDebug() << "Configuration file" << fileName << "was loaded."; } void overrideSettings(QSettings &settings, int argc, char **argv) { - // Options like -DMy/setting=test + // Options like -D My/setting=test QRegExp rx("([^=]+)=(.*)"); - QMap settingOptions; for (int i = 0; i < argc; ++i) { - if (QString(CONFIG_OPTION).compare(QString(argv[i])) == 0) { + if (CONFIG_OPTION == QString(argv[i])) { if (rx.indexIn(argv[++i]) > -1) { - settingOptions.insert(rx.cap(1), rx.cap(2)); + QString key = rx.cap(1); + QString value = rx.cap(2); + qDebug() << "User setting" << key << "set to value" << value; + settings.setValue(key, value); } } - if (QString(CLEAN_CONFIG_OPTION).compare(QString(argv[i])) == 0) { - settings.clear(); - } - } - - QList keys = settingOptions.keys(); - foreach (QString key, keys) { - qDebug() << "Overriding user setting:" << key << "with value" << settingOptions.value(key); - settings.setValue(key, settingOptions.value(key)); } settings.sync(); @@ -364,7 +395,8 @@ namespace { void loadTranslators(QString language, QTranslator &translator, QTranslator &qtTranslator) { - const QString &creatorTrPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH) + QLatin1String("/translations"); + const QString &creatorTrPath = QCoreApplication::applicationDirPath() + SHARE_PATH + + QLatin1String("/translations"); if (translator.load(QLatin1String("openpilotgcs_") + language, creatorTrPath)) { const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath); const QString &qtTrFile = QLatin1String("qt_") + language; @@ -390,7 +422,7 @@ int main(int argc, char **argv) systemInit(); // create application - SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv); + SharedTools::QtSingleApplication app(APP_NAME, argc, argv); // initialize the plugin manager ExtensionSystem::PluginManager pluginManager; @@ -398,9 +430,9 @@ int main(int argc, char **argv) pluginManager.setPluginPaths(getPluginPaths()); // parse command line - qDebug() << "Command line" << app.arguments();; + qDebug() << "Command line" << app.arguments(); QString errorMessage; - FoundAppOptions foundAppOptions = parseCommandLine(app, pluginManager, errorMessage); + AppOptionValues appOptionValues = parseCommandLine(app, pluginManager, errorMessage); if (!errorMessage.isEmpty()) { // this will display two popups : one error popup + one usage string popup // TODO merge two popups into one. @@ -412,14 +444,14 @@ int main(int argc, char **argv) // load user settings // Must be done before any QSettings class is created // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp - QString settingsPath = QCoreApplication::applicationDirPath() + QLatin1String(SHARE_PATH); - qDebug() << "Loading user settings from" << settingsPath; + QString settingsPath = QCoreApplication::applicationDirPath() + SHARE_PATH; + qDebug() << "Loading system settings from" << settingsPath; QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, settingsPath); - QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, QLatin1String("OpenPilot"), - QLatin1String("OpenPilotGCS_config")); + qDebug() << "Loading user settings from" << SETTINGS_ORG_NAME << "/" << SETTINGS_APP_NAME; + QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, SETTINGS_ORG_NAME, SETTINGS_APP_NAME); // need to reset all user settings? - if (foundAppOptions.contains(RESET)) { + if (appOptionValues.contains(RESET_OPTION)) { qDebug() << "Resetting user settings!"; settings.clear(); } @@ -428,7 +460,7 @@ int main(int argc, char **argv) if (!settings.allKeys().count()) { // no user settings, load the factory defaults qDebug() << "No user settings found, loading factory defaults..."; - loadFactoryDefaults(settings); + loadFactoryDefaults(settings, appOptionValues); } // override settings with command line provided values @@ -453,30 +485,36 @@ int main(int argc, char **argv) // the language used is defined by the General/OverrideLanguage setting (defaults to GCS locale) // if the translation file for the given language is not found, GCS will default to built in English. QString language = settings.value("General/OverrideLanguage", localeName).toString(); - qDebug() << "main - translation language:" << language; + qDebug() << "main - language:" << language; QTranslator translator; QTranslator qtTranslator; loadTranslators(language, translator, qtTranslator); app.setProperty("qtc_locale", localeName); // Do we need this? + if (appOptionValues.contains(EXIT_AFTER_CONFIG_OPTION)) { + qDebug() << "main - exiting after config!"; + return 0; + } + // open the splash screen GCSSplashScreen *splash = 0; - if (!foundAppOptions.contains(NO_SPLASH)) { + if (!appOptionValues.contains(NO_SPLASH_OPTION)) { splash = new GCSSplashScreen(); // show splash splash->showProgressMessage(QObject::tr("Application starting...")); splash->show(); // connect to track progress of plugin manager - QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)), - splash, SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*))); + QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)), splash, + SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*))); } // find and load core plugin const PluginSpecSet plugins = pluginManager.plugins(); ExtensionSystem::PluginSpec *coreplugin = 0; - foreach (ExtensionSystem::PluginSpec *spec, plugins) { - if (spec->name() == QLatin1String(corePluginNameC)) { + foreach (ExtensionSystem::PluginSpec *spec, plugins) + { + if (spec->name() == CORE_PLUGIN_NAME) { coreplugin = spec; break; } @@ -493,23 +531,18 @@ int main(int argc, char **argv) return 1; } - if (foundAppOptions.contains(VERSION_OPTION)) { + if (appOptionValues.contains(VERSION_OPTION)) { printVersion(coreplugin, pluginManager); return 0; } - if (foundAppOptions.contains(EXIT_AFTER_CONFIG_OPTION)) { - return 0; - } - if (foundAppOptions.contains(HELP_OPTION1) - || foundAppOptions.contains(HELP_OPTION2) - || foundAppOptions.contains(HELP_OPTION3) - || foundAppOptions.contains(HELP_OPTION4)) { + if (appOptionValues.contains(HELP1_OPTION) || appOptionValues.contains(HELP2_OPTION) + || appOptionValues.contains(HELP3_OPTION) || appOptionValues.contains(HELP4_OPTION)) { printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager); return 0; } const bool isFirstInstance = !app.isRunning(); - if (!isFirstInstance && foundAppOptions.contains(CLIENT_OPTION)) { + if (!isFirstInstance && appOptionValues.contains(CLIENT_OPTION)) { return sendArguments(app, pluginManager.arguments()) ? 0 : -1; } @@ -522,7 +555,8 @@ int main(int argc, char **argv) { QStringList errors; - foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) { + foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) + { if (p->hasError()) { errors.append(p->errorString()); } From f7236eb180681e8ce9c44ed48df366506412c449 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 18 Apr 2013 15:45:38 +0300 Subject: [PATCH 22/34] tools: add Linux 64bit native ARM toolchain --- make/tools.mk | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/make/tools.mk b/make/tools.mk index ccf59a4c2..adac4a631 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -52,15 +52,16 @@ endif ############################## ifeq ($(UNAME), Linux) - ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux.tar.bz2 ifeq ($(ARCH), x86_64) - QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-linux-x64.tar.bz2 + ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-amd64.tar.bz2 + QT_SDK_URL := "Plese use native Qt 4.8.x package" else - QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-linux.tar.bz2 + ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-i686.tar.bz2 + QT_SDK_URL := "Plese use native Qt 4.8.x package" endif else ifeq ($(UNAME), Darwin) ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-mac.tar.bz2 - QT_SDK_URL := TODO/qt-4.8.4-mac.tar.bz2 + QT_SDK_URL := "Plese use native Qt 4.8.x package" else ifeq ($(UNAME), Windows) ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-windows.tar.bz2 QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-windows.tar.bz2 From b7de3c99d8de804ff79699e04b57e3ce85404a70 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 18 Apr 2013 16:03:05 +0200 Subject: [PATCH 23/34] tools: fix typo in comments --- make/tools.mk | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/make/tools.mk b/make/tools.mk index adac4a631..e15d2a69f 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -54,14 +54,14 @@ endif ifeq ($(UNAME), Linux) ifeq ($(ARCH), x86_64) ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-amd64.tar.bz2 - QT_SDK_URL := "Plese use native Qt 4.8.x package" + QT_SDK_URL := "Please install native Qt 4.8.x SDK using package manager" else ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-i686.tar.bz2 - QT_SDK_URL := "Plese use native Qt 4.8.x package" + QT_SDK_URL := "Please install native Qt 4.8.x SDK using package manager" endif else ifeq ($(UNAME), Darwin) ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-mac.tar.bz2 - QT_SDK_URL := "Plese use native Qt 4.8.x package" + QT_SDK_URL := "Please install native Qt 4.8.x SDK using package manager" else ifeq ($(UNAME), Windows) ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-windows.tar.bz2 QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-windows.tar.bz2 From 509a1b4fe16f0410e360038618416177e08fedc3 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 18 Apr 2013 17:37:12 +0300 Subject: [PATCH 24/34] make: fix *_program targets (were broken for firmware) --- make/apps-defs.mk | 6 ++++++ make/boot-defs.mk | 3 +++ make/common-defs.mk | 6 ------ 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/make/apps-defs.mk b/make/apps-defs.mk index 20bb858c0..08c6c8211 100644 --- a/make/apps-defs.mk +++ b/make/apps-defs.mk @@ -175,3 +175,9 @@ ifeq ($(MCU),cortex-m3) else ifeq ($(MCU),cortex-m4) LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) endif + +# Add opfw target +$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) + +# Add jtag targets (program and wipe) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) diff --git a/make/boot-defs.mk b/make/boot-defs.mk index 1e8652be4..e6aaeb22e 100644 --- a/make/boot-defs.mk +++ b/make/boot-defs.mk @@ -126,3 +126,6 @@ ifeq ($(MCU),cortex-m3) else ifeq ($(MCU),cortex-m4) LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_BL)) endif + +# Add jtag targets (program and wipe) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) diff --git a/make/common-defs.mk b/make/common-defs.mk index 9b927a9a8..6663c8ca2 100644 --- a/make/common-defs.mk +++ b/make/common-defs.mk @@ -225,12 +225,6 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin -# Add opfw target -$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) - -# Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) - .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf lss: $(OUTDIR)/$(TARGET).lss From f15249ff07d1dc60b07d80dc1ddaed376cc94f33 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 18 Apr 2013 17:50:34 +0300 Subject: [PATCH 25/34] make: fix bu_* targets --- make/apps-defs.mk | 3 --- make/common-defs.mk | 3 +++ 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/make/apps-defs.mk b/make/apps-defs.mk index 08c6c8211..e8ff9a016 100644 --- a/make/apps-defs.mk +++ b/make/apps-defs.mk @@ -176,8 +176,5 @@ else ifeq ($(MCU),cortex-m4) LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) endif -# Add opfw target -$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) - # Add jtag targets (program and wipe) $(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) diff --git a/make/common-defs.mk b/make/common-defs.mk index 6663c8ca2..97ee3a818 100644 --- a/make/common-defs.mk +++ b/make/common-defs.mk @@ -223,6 +223,9 @@ $(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) # Compile: create assembler files from C source files. ARM only $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) +# Add opfw target +$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) + $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin .PHONY: elf lss sym hex bin bino opfw From 72a2d1a50e8123735199404c676f0659d8734baa Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 19 Apr 2013 18:47:56 +0300 Subject: [PATCH 26/34] style: use 2 spaces and full stop for UAVO comments (as used in other objects) +review OPReview-430 --- shared/uavobjectdefinition/systemalarms.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index 8780d031d..e3d12baa6 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -1,6 +1,6 @@ - Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules.Some modules may have a module defined Status and Substatus fields that details its condition + Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. Some modules may have a module defined Status and Substatus fields that details its condition. SystemConfiguration From 491e89b1654de5396d8a6871e0cc0d1f7b6feb45 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 19 Apr 2013 20:43:31 +0200 Subject: [PATCH 27/34] make: sort wildcard sources to make binaries identical on all platforms Thanks to Amedee for finding the cause of the difference and CorvusCorax for participating in the discussion. --- flight/PiOS/Common/Libraries/CMSIS2/library.mk | 2 +- flight/PiOS/Common/Libraries/FreeRTOS/library.mk | 2 +- flight/PiOS/Common/Libraries/dosfs/library.mk | 2 +- flight/PiOS/Common/Libraries/msheap/library.mk | 2 +- flight/PiOS/STM32F10x/library.mk | 10 +++++----- flight/PiOS/STM32F4xx/library.mk | 10 +++++----- flight/PiOS/posix/Libraries/FreeRTOS/library.mk | 2 +- flight/PiOS/posix/library.mk | 6 +++--- make/apps-defs.mk | 4 ++-- 9 files changed, 20 insertions(+), 20 deletions(-) diff --git a/flight/PiOS/Common/Libraries/CMSIS2/library.mk b/flight/PiOS/Common/Libraries/CMSIS2/library.mk index fd9410ad0..e7d8e8572 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/library.mk +++ b/flight/PiOS/Common/Libraries/CMSIS2/library.mk @@ -11,7 +11,7 @@ ifeq ($(USE_DSP_LIB), YES) CMSIS_DSPLIB := $(CMSIS2_DIR)DSP_Lib/Source # Compile all files into output directory - DSPLIB_SRC := $(wildcard $(CMSIS_DSPLIB)/*/*.c) + DSPLIB_SRC := $(sort $(wildcard $(CMSIS_DSPLIB)/*/*.c)) DSPLIB_SRCBASE := $(notdir $(basename $(DSPLIB_SRC))) $(foreach src, $(DSPLIB_SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/library.mk b/flight/PiOS/Common/Libraries/FreeRTOS/library.mk index 9e101b273..70005c3c6 100644 --- a/flight/PiOS/Common/Libraries/FreeRTOS/library.mk +++ b/flight/PiOS/Common/Libraries/FreeRTOS/library.mk @@ -6,5 +6,5 @@ # FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source -SRC += $(wildcard $(FREERTOS_DIR)/*.c) +SRC += $(sort $(wildcard $(FREERTOS_DIR)/*.c)) EXTRAINCDIRS += $(FREERTOS_DIR)/include diff --git a/flight/PiOS/Common/Libraries/dosfs/library.mk b/flight/PiOS/Common/Libraries/dosfs/library.mk index 0e6fa982e..4b8499788 100644 --- a/flight/PiOS/Common/Libraries/dosfs/library.mk +++ b/flight/PiOS/Common/Libraries/dosfs/library.mk @@ -3,5 +3,5 @@ # DOSFS_DIR := $(dir $(lastword $(MAKEFILE_LIST))) -SRC += $(wildcard $(DOSFS_DIR)*.c) +SRC += $(sort $(wildcard $(DOSFS_DIR)*.c)) EXTRAINCDIRS += $(DOSFS_DIR) diff --git a/flight/PiOS/Common/Libraries/msheap/library.mk b/flight/PiOS/Common/Libraries/msheap/library.mk index 84a796e62..80a8b7e25 100644 --- a/flight/PiOS/Common/Libraries/msheap/library.mk +++ b/flight/PiOS/Common/Libraries/msheap/library.mk @@ -3,5 +3,5 @@ # MSHEAP_DIR := $(dir $(lastword $(MAKEFILE_LIST))) -SRC += $(wildcard $(MSHEAP_DIR)*.c) +SRC += $(sort $(wildcard $(MSHEAP_DIR)*.c)) EXTRAINCDIRS += $(MSHEAP_DIR) diff --git a/flight/PiOS/STM32F10x/library.mk b/flight/PiOS/STM32F10x/library.mk index df95cfc72..d0d5a0809 100644 --- a/flight/PiOS/STM32F10x/library.mk +++ b/flight/PiOS/STM32F10x/library.mk @@ -18,7 +18,7 @@ ARCHFLAGS += -mcpu=cortex-m3 --specs=nano.specs ASRC += $(PIOS_DEVLIB)startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S # PIOS device library source and includes -SRC += $(wildcard $(PIOS_DEVLIB)*.c) +SRC += $(sort $(wildcard $(PIOS_DEVLIB)*.c)) # CMSIS for the F1 include $(PIOS)/Common/Libraries/CMSIS2/library.mk @@ -29,12 +29,12 @@ EXTRAINCDIRS += $(CMSIS_DIR) # ST Peripheral library PERIPHLIB = $(PIOS_DEVLIB)Libraries/STM32F10x_StdPeriph_Driver -SRC += $(wildcard $(PERIPHLIB)/src/*.c) +SRC += $(sort $(wildcard $(PERIPHLIB)/src/*.c)) EXTRAINCDIRS += $(PERIPHLIB)/inc # ST USB Device library USBDEVLIB = $(PIOS_DEVLIB)Libraries/STM32_USB-FS-Device_Driver -SRC += $(wildcard $(USBDEVLIB)/src/*.c) +SRC += $(sort $(wildcard $(USBDEVLIB)/src/*.c)) EXTRAINCDIRS += $(USBDEVLIB)/inc # @@ -45,7 +45,7 @@ EXTRAINCDIRS += $(USBDEVLIB)/inc # ifneq ($(FREERTOS_DIR),) FREERTOS_PORTDIR := $(PIOS_DEVLIB)Libraries/FreeRTOS/Source - SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3/*.c) - SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/heap_1.c) + SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3/*.c)) + SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/heap_1.c)) EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3 endif diff --git a/flight/PiOS/STM32F4xx/library.mk b/flight/PiOS/STM32F4xx/library.mk index 531dbbfb2..a38b2720d 100644 --- a/flight/PiOS/STM32F4xx/library.mk +++ b/flight/PiOS/STM32F4xx/library.mk @@ -20,18 +20,18 @@ CDEFS += -DARM_MATH_CM4 -D__FPU_PRESENT=1 ARCHFLAGS += -mcpu=cortex-m4 -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard # PIOS device library source and includes -SRC += $(wildcard $(PIOS_DEVLIB)*.c) +SRC += $(sort $(wildcard $(PIOS_DEVLIB)*.c)) EXTRAINCDIRS += $(PIOS_DEVLIB)inc # CMSIS for the F4 include $(PIOSCOMMON)/Libraries/CMSIS2/library.mk CMSIS2_DEVICEDIR := $(PIOS_DEVLIB)Libraries/CMSIS2/Device/ST/STM32F4xx -SRC += $(wildcard $(CMSIS2_DEVICEDIR)/Source/$(BOARD_NAME)/*.c) +SRC += $(sort $(wildcard $(CMSIS2_DEVICEDIR)/Source/$(BOARD_NAME)/*.c)) EXTRAINCDIRS += $(CMSIS2_DEVICEDIR)/Include # ST Peripheral library PERIPHLIB = $(PIOS_DEVLIB)Libraries/STM32F4xx_StdPeriph_Driver -SRC += $(wildcard $(PERIPHLIB)/src/*.c) +SRC += $(sort $(wildcard $(PERIPHLIB)/src/*.c)) EXTRAINCDIRS += $(PERIPHLIB)/inc # ST USB OTG library @@ -42,7 +42,7 @@ EXTRAINCDIRS += $(USBOTGLIB)/inc # ST USB Device library USBDEVLIB = $(PIOS_DEVLIB)Libraries/STM32_USB_Device_Library -SRC += $(wildcard $(USBDEVLIB)/Core/src/*.c) +SRC += $(sort $(wildcard $(USBDEVLIB)/Core/src/*.c)) EXTRAINCDIRS += $(USBDEVLIB)/Core/inc # @@ -53,7 +53,7 @@ EXTRAINCDIRS += $(USBDEVLIB)/Core/inc # ifneq ($(FREERTOS_DIR),) FREERTOS_PORTDIR := $(PIOS_DEVLIB)Libraries/FreeRTOS/Source - SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F/*.c) + SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F/*.c)) EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F include $(PIOSCOMMON)/Libraries/msheap/library.mk endif diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/library.mk b/flight/PiOS/posix/Libraries/FreeRTOS/library.mk index c6267255f..08381319f 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/library.mk +++ b/flight/PiOS/posix/Libraries/FreeRTOS/library.mk @@ -6,5 +6,5 @@ # FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source -SRC += $(wildcard $(FREERTOS_DIR)/*.c) +SRC += $(sort $(wildcard $(FREERTOS_DIR)/*.c)) EXTRAINCDIRS += $(FREERTOS_DIR)/include diff --git a/flight/PiOS/posix/library.mk b/flight/PiOS/posix/library.mk index 530431210..79cadc5c7 100644 --- a/flight/PiOS/posix/library.mk +++ b/flight/PiOS/posix/library.mk @@ -27,7 +27,7 @@ ARCHFLAGS += -DARCH_POSIX # # PIOS device library source and includes # -SRC += $(wildcard $(PIOS_DEVLIB)*.c) +SRC += $(sort $(wildcard $(PIOS_DEVLIB)*.c)) EXTRAINCDIRS += $(PIOS_DEVLIB)/inc # @@ -68,8 +68,8 @@ EXTRAINCDIRS += $(PIOS_DEVLIB)/inc # ifneq ($(FREERTOS_DIR),) FREERTOS_PORTDIR := $(PIOS_DEVLIB)/Libraries/FreeRTOS/Source -SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/Posix/*.c) -SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/*.c) +SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/Posix/*.c)) +SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/*.c)) EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/Posix endif diff --git a/make/apps-defs.mk b/make/apps-defs.mk index e8ff9a016..1f23dc493 100644 --- a/make/apps-defs.mk +++ b/make/apps-defs.mk @@ -101,8 +101,8 @@ SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/pid.c ## Modules -SRC += $(foreach mod, $(MODULES), $(wildcard $(OPMODULEDIR)/$(mod)/*.c)) -SRC += $(foreach mod, $(OPTMODULES), $(wildcard $(OPMODULEDIR)/$(mod)/*.c)) +SRC += $(foreach mod, $(MODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.c))) +SRC += $(foreach mod, $(OPTMODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.c))) # Declare all non-optional modules as built-in to force inclusion. # Built-in modules are always enabled and cannot be disabled. From 5e942bbd6dc166cded71b2a8e00306dc87a76532 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 19 Apr 2013 22:54:55 +0300 Subject: [PATCH 28/34] gcs: fix weird Windows build error if python is called w/o quotes This fixes two problems: - if OPENPILOT_TOOLS_DIR is set using backslashes, they should be converted to forward ones. Otherwise on Windows it can't run the program. - for some weird reason the python called without quotes (regardless of full path used or not) tries to open whole command line as a file instead of the 1st parameter only. This works as it should from bash prompt. But executed by make it fails on Windows. --- ground/openpilotgcs/src/app/gcsversioninfo.pri | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/app/gcsversioninfo.pri b/ground/openpilotgcs/src/app/gcsversioninfo.pri index 42a695695..cc1d9c629 100644 --- a/ground/openpilotgcs/src/app/gcsversioninfo.pri +++ b/ground/openpilotgcs/src/app/gcsversioninfo.pri @@ -17,16 +17,17 @@ PYTHON_DIR = python-2.7.4 # Search the python using environment override first OPENPILOT_TOOLS_DIR = $$(OPENPILOT_TOOLS_DIR) !isEmpty(OPENPILOT_TOOLS_DIR):exists($$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python*) { - PYTHON = $$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python + PYTHON = \"$$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python\" } else { # If not found, search the predefined tools path exists($$ROOT_DIR/tools/$$PYTHON_DIR/python*) { - PYTHON = $$ROOT_DIR/tools/$$PYTHON_DIR/python + PYTHON = \"$$ROOT_DIR/tools/$$PYTHON_DIR/python\" } else { # not found, hope it's in the path... - PYTHON = python + PYTHON = \"python\" } } + PYTHON = $$replace(PYTHON, \\\\, /) message(Using python interpreter: $$PYTHON) # Define other variables From 343a4b9015f8fa577987bc12691ae6de10f8f939 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 20 Apr 2013 00:56:45 +0300 Subject: [PATCH 29/34] OP-886: cosmetic style and spacing fixes --- flight/Libraries/alarms.c | 11 ++++------- flight/Modules/System/systemmod.c | 13 ++++++++----- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/flight/Libraries/alarms.c b/flight/Libraries/alarms.c index 94a1006ef..e0da51185 100644 --- a/flight/Libraries/alarms.c +++ b/flight/Libraries/alarms.c @@ -157,8 +157,7 @@ int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) */ void AlarmsDefaultAll() { - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { + for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { AlarmsDefault(n); } } @@ -182,8 +181,7 @@ int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) */ void AlarmsClearAll() { - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { + for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { AlarmsClear(n); } } @@ -224,7 +222,6 @@ int32_t AlarmsHasCritical() static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) { SystemAlarmsData alarms; - uint32_t n; // Lock xSemaphoreTakeRecursive(lock, portMAX_DELAY); @@ -233,7 +230,7 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) SystemAlarmsGet(&alarms); // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { + for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { if (alarms.Alarm[n] >= severity) { xSemaphoreGiveRecursive(lock); return 1; @@ -244,8 +241,8 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) xSemaphoreGiveRecursive(lock); return 0; } + /** * @} * @} */ - diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 5de110488..4b8cc6772 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -39,8 +39,10 @@ */ #include + // private includes #include "inc/systemmod.h" + // UAVOs #include #include @@ -51,6 +53,7 @@ #include #include #include + // Flight Libraries #include @@ -69,8 +72,8 @@ #ifndef IDLE_COUNTS_PER_SEC_AT_NO_LOAD #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 995998 // calibrated by running tests/test_cpuload.c - // must be updated if the FreeRTOS or compiler - // optimisation options are changed. + // must be updated if the FreeRTOS or compiler + // optimisation options are changed. #endif #if defined(PIOS_SYSTEM_STACK_SIZE) @@ -177,8 +180,8 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); - // Load a copy of HwSetting active at boot time - HwSettingsGet(&bootHwSettings); + // Load a copy of HwSetting active at boot time + HwSettingsGet(&bootHwSettings); // Whenever the configuration changes, make sure it is safe to fly HwSettingsConnectCallback(hwSettingsUpdatedCb); @@ -314,7 +317,7 @@ static void objectUpdatedCb(UAVObjEvent * ev) #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) retval = PIOS_FLASHFS_Format(0); #else - retval = -1; + retval = -1; #endif } switch(retval) { From 6074828807cc56cc22dae7588dca3dfa12c39e62 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 20 Apr 2013 00:04:06 +0200 Subject: [PATCH 30/34] OP-769 main.cpp fixed review comments (OPReview-440) --- ground/openpilotgcs/src/app/main.cpp | 66 ++++++++++++---------------- 1 file changed, 27 insertions(+), 39 deletions(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index 4db9e429a..ba237041d 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -39,7 +39,7 @@ The -reset switch will clear all the user settings and will trigger a reload of the factory defaults. - You can combine it with the -configfile= command line argument to quickly switch between multiple settings files. + You can combine it with the -config-file= command line argument to quickly switch between multiple settings files. [code] openpilotgcs -reset -config-file ./MyOpenPilotGCS.xml @@ -55,7 +55,7 @@ Quickly switch configurations [code] - -reset -config-file + openpilotgcs -reset -config-file [/code] Configuring GCS from installer @@ -65,14 +65,14 @@ If the user chooses to start GCS at the end of the installer: [code] - -D General/OverrideLanguage=de + openpilotgcs -D General/OverrideLanguage=de [/code] If the user chooses not to start GCS at the end of the installer, you still need to configure GCS. In that case you can use -exit-after-config [code] - -D General/OverrideLanguage=de -exit-after-config + openpilotgcs -D General/OverrideLanguage=de -exit-after-config [/code] */ @@ -127,7 +127,7 @@ namespace { const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml"; - const char *fixedOptionsC = " [OPTION]... [FILE]...\n" + const char *fixedOptionsC = " [OPTION]...\n" "Options:\n" " -help Display this help\n" " -version Display application version\n" @@ -151,66 +151,56 @@ namespace { const QLatin1String EXIT_AFTER_CONFIG_OPTION("-exit-after-config"); // Helpers for displaying messages. Note that there is no console on Windows. -#ifdef Q_OS_WIN - - // Format as
 HTML
-    inline void toHtml(QString &t)
+    void displayHelpText(QString t)
     {
+#ifdef Q_OS_WIN
+        // No console on Windows. (???)
+        // TODO there is a console on windows and popups are not always desired
         t.replace(QLatin1Char('&'), QLatin1String("&"));
         t.replace(QLatin1Char('<'), QLatin1String("<"));
         t.replace(QLatin1Char('>'), QLatin1String(">"));
         t.insert(0, QLatin1String("
"));
         t.append(QLatin1String("
")); - } - - void displayHelpText(QString t) // No console on Windows. - { - toHtml(t); QMessageBox::information(0, APP_NAME, t); - } - - void displayError(const QString &t) // No console on Windows. - { - QMessageBox::critical(0, APP_NAME, t); - } - #else - - void displayHelpText(const QString &t) - { qWarning("%s", qPrintable(t)); +#endif } void displayError(const QString &t) { +#ifdef Q_OS_WIN + // No console on Windows. (???) + // TODO there is a console on windows and popups are not always desired + QMessageBox::critical(0, APP_NAME, t); +#else qCritical("%s", qPrintable(t)); +#endif } -#endif - - void printVersion(const ExtensionSystem::PluginSpec *coreplugin, const ExtensionSystem::PluginManager &pm) + void printVersion(const ExtensionSystem::PluginSpec *corePlugin, const ExtensionSystem::PluginManager &pm) { QString version; QTextStream str(&version); - str << '\n' << APP_NAME << ' ' << coreplugin->version() << " based on Qt " << qVersion() << "\n\n"; + str << '\n' << APP_NAME << ' ' << corePlugin->version() << " based on Qt " << qVersion() << "\n\n"; pm.formatPluginVersions(str); - str << '\n' << coreplugin->copyright() << '\n'; + str << '\n' << corePlugin->copyright() << '\n'; displayHelpText(version); } - void printHelp(const QString &a0, const ExtensionSystem::PluginManager &pm) + void printHelp(const QString &appExecName, const ExtensionSystem::PluginManager &pm) { QString help; QTextStream str(&help); - str << "Usage: " << a0 << fixedOptionsC; + str << "Usage: " << appExecName << fixedOptionsC; ExtensionSystem::PluginManager::formatOptions(str, OptionIndent, DescriptionIndent); pm.formatPluginOptions(str, OptionIndent, DescriptionIndent); displayHelpText(help); } - inline QString msgCoreLoadFailure(const QString &why) + inline QString msgCoreLoadFailure(const QString &reason) { - return QCoreApplication::translate("Application", "Failed to load core: %1").arg(why); + return QCoreApplication::translate("Application", "Failed to load core plug-in, reason is: %1").arg(reason); } inline QString msgSendArgumentFailed() @@ -366,8 +356,7 @@ namespace { // transfer loaded settings to application settings QStringList keys = qs.allKeys(); - foreach(QString key, keys) - { + foreach(QString key, keys) { settings.setValue(key, qs.value(key)); } @@ -469,7 +458,7 @@ int main(int argc, char **argv) overrideSettings(settings, argc, argv); // initialize GCS locale - // use the value defined by the General/Locale setting or default to system locale. + // use the value defined by the General/Locale setting or default to system Locale. // the General/Locale setting is not available in the Options dialog, it is a hidden setting but can still be changed: // - through the command line // - editing the factory defaults XML file before 1st launch @@ -477,7 +466,7 @@ int main(int argc, char **argv) QString localeName = settings.value("General/Locale", QLocale::system().name()).toString(); QLocale::setDefault(localeName); - // some debuging + // some debugging qDebug() << "main - system locale:" << QLocale::system().name(); qDebug() << "main - GCS locale:" << QLocale().name(); @@ -512,8 +501,7 @@ int main(int argc, char **argv) // find and load core plugin const PluginSpecSet plugins = pluginManager.plugins(); ExtensionSystem::PluginSpec *coreplugin = 0; - foreach (ExtensionSystem::PluginSpec *spec, plugins) - { + foreach (ExtensionSystem::PluginSpec *spec, plugins) { if (spec->name() == CORE_PLUGIN_NAME) { coreplugin = spec; break; From 220b4b504256341512a5ec90a47e9059a45036ce Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 20 Apr 2013 02:10:40 +0300 Subject: [PATCH 31/34] OP-886: use enum for extended alarm status field See also: http://reviews.openpilot.org/cru/OPReview-430 http://progress.openpilot.org/browse/OP-915 --- flight/Libraries/alarms.c | 11 +++++++---- flight/Libraries/inc/alarms.h | 5 ++++- flight/Libraries/inc/sanitycheck.h | 8 +------- flight/Libraries/sanitycheck.c | 7 +++---- flight/Modules/System/systemmod.c | 2 +- shared/uavobjectdefinition/systemalarms.xml | 7 ++++++- 6 files changed, 22 insertions(+), 18 deletions(-) diff --git a/flight/Libraries/alarms.c b/flight/Libraries/alarms.c index e0da51185..b3706ba24 100644 --- a/flight/Libraries/alarms.c +++ b/flight/Libraries/alarms.c @@ -91,11 +91,14 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity * Set an Extended Alarm * @param alarm The system alarm to be modified * @param severity The alarm severity - * @param status: the Extended alarm status field - * @param subStatus: the Extended alarm substatus field + * @param status The Extended alarm status field + * @param subStatus The Extended alarm substatus field * @return 0 if success, -1 if an error */ -int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity, uint8_t status, uint8_t subStatus) +int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, + SystemAlarmsAlarmOptions severity, + SystemAlarmsExtendedAlarmStatusOptions status, + uint8_t subStatus) { SystemAlarmsData alarms; @@ -170,7 +173,7 @@ void AlarmsDefaultAll() int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) { if (alarm < SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) { - return ExtendedAlarmsSet(alarm, SYSTEMALARMS_ALARM_OK, 0, 0); + return ExtendedAlarmsSet(alarm, SYSTEMALARMS_ALARM_OK, SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE, 0); } else { return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); } diff --git a/flight/Libraries/inc/alarms.h b/flight/Libraries/inc/alarms.h index dc785015e..e91a3be55 100644 --- a/flight/Libraries/inc/alarms.h +++ b/flight/Libraries/inc/alarms.h @@ -33,7 +33,10 @@ int32_t AlarmsInitialize(void); int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity, uint8_t status, uint8_t subStatus); +int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, + SystemAlarmsAlarmOptions severity, + SystemAlarmsExtendedAlarmStatusOptions status, + uint8_t subStatus); SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); void AlarmsDefaultAll(); diff --git a/flight/Libraries/inc/sanitycheck.h b/flight/Libraries/inc/sanitycheck.h index 9ee72f3c5..b7fd74ca3 100644 --- a/flight/Libraries/inc/sanitycheck.h +++ b/flight/Libraries/inc/sanitycheck.h @@ -29,15 +29,9 @@ #ifndef SANITYCHECK_H #define SANITYCHECK_H -#define SANITYCHECK_STATUS_ERROR_NONE 0 -#define SANITYCHECK_STATUS_ERROR_FLIGHTMODE 1 - -#define BOOTFAULT_STATUS_ERROR_NONE 0 -#define BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT 1 - #if (SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM != SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM) || \ (SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM > SYSTEMALARMS_ALARM_NUMELEM) -#error incongruent SystemAlarms. Please revise the UAVO definition in SystemAlarm.xml +#error Incongruent SystemAlarms. Please revise the UAVO definition in systemalarms.xml #endif extern int32_t configuration_check(); diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index c98369597..07940d764 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -54,7 +54,7 @@ static int32_t check_stabilization_settings(int index, bool multirotor); int32_t configuration_check() { int32_t severity = SYSTEMALARMS_ALARM_OK; - uint8_t alarmstatus = SANITYCHECK_STATUS_ERROR_NONE; + SystemAlarmsExtendedAlarmStatusOptions alarmstatus = SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE; uint8_t alarmsubstatus = 0; // Get board type const struct pios_board_info * bdinfo = &pios_board_info_blob; @@ -134,9 +134,8 @@ int32_t configuration_check() severity = SYSTEMALARMS_ALARM_ERROR; } // mark the first encountered erroneous setting in status and substatus - if(severity != SYSTEMALARMS_ALARM_OK && alarmstatus == SANITYCHECK_STATUS_ERROR_NONE) - { - alarmstatus = SANITYCHECK_STATUS_ERROR_FLIGHTMODE; + if ((severity != SYSTEMALARMS_ALARM_OK) && (alarmstatus == SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE)) { + alarmstatus = SYSTEMALARMS_EXTENDEDALARMSTATUS_FLIGHTMODE; alarmsubstatus = i; } diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 4b8cc6772..b3f5f6db8 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -344,7 +344,7 @@ static void hwSettingsUpdatedCb(UAVObjEvent * ev) HwSettingsGet(¤tHwSettings); // check whether the Hw Configuration has changed from the one used at boot time if (memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0) { - ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_ERROR, BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT, 0); + ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_ERROR, SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED, 0); } } diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index b34bd1612..fedeef14a 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -23,11 +23,16 @@ Power - + SystemConfiguration BootFault + + + + + From cfbd9b2728fed3f7c27d32e2d8af7454c4799ead Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 20 Apr 2013 14:04:28 +0200 Subject: [PATCH 32/34] OP-769 main.cpp various cleanups --- ground/openpilotgcs/src/app/main.cpp | 29 +++++++++++++--------------- 1 file changed, 13 insertions(+), 16 deletions(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index ba237041d..a9183f0af 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -100,7 +100,6 @@ #include #include #include -#include namespace { @@ -108,9 +107,8 @@ namespace { typedef QMap AppOptions; typedef QMap AppOptionValues; - enum { - OptionIndent = 4, DescriptionIndent = 24 - }; + const int OptionIndent = 4; + const int DescriptionIndent = 24; const QLatin1String APP_NAME("OpenPilot GCS"); @@ -127,7 +125,7 @@ namespace { const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml"; - const char *fixedOptionsC = " [OPTION]...\n" + const char *fixedOptionsC = " [OPTION]... [FILE]...\n" "Options:\n" " -help Display this help\n" " -version Display application version\n" @@ -211,16 +209,16 @@ namespace { // Prepare a remote argument: If it is a relative file, add the current directory // since the the central instance might be running in a different directory. - inline QString prepareRemoteArgument(const QString &a) + inline QString prepareRemoteArgument(const QString &arg) { - QFileInfo fi(a); + QFileInfo fi(arg); if (!fi.exists()) { - return a; + return arg; } if (fi.isRelative()) { return fi.absoluteFilePath(); } - return a; + return arg; } // Send the arguments to an already running instance of application @@ -321,12 +319,12 @@ namespace { // check if command line option -config-file contains a file name QString commandLine = appOptionValues.value(CONFIG_FILE_OPTION); if (!commandLine.isEmpty()) { - if (QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) { + QFileInfo fi(commandLine); + if (fi.isRelative()) { // file name specified on command line has a relative path - fileName = directory.absolutePath() + QDir::separator() + commandLine; - qDebug() << "Configuration file" << fileName << "specified on command line will be loaded."; - } else if (QFile::exists(commandLine)) { - // file name specified on command line has an absolutee path + commandLine = directory.absolutePath() + QDir::separator() + commandLine; + } + if (QFile::exists(commandLine)) { fileName = commandLine; qDebug() << "Configuration file" << fileName << "specified on command line will be loaded."; } else { @@ -543,8 +541,7 @@ int main(int argc, char **argv) { QStringList errors; - foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) - { + foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) { if (p->hasError()) { errors.append(p->errorString()); } From dd37c31a0713ccdf82a8566d267192a8f16550dd Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sat, 20 Apr 2013 13:59:25 +0200 Subject: [PATCH 33/34] OP-886 Fixes to styles, used enum for ExtendedAlarmStatus Conflicts: flight/Libraries/inc/sanitycheck.h shared/uavobjectdefinition/systemalarms.xml --- flight/Libraries/inc/sanitycheck.h | 8 ++++++++ flight/Libraries/sanitycheck.c | 1 - 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/flight/Libraries/inc/sanitycheck.h b/flight/Libraries/inc/sanitycheck.h index b7fd74ca3..214b50cfc 100644 --- a/flight/Libraries/inc/sanitycheck.h +++ b/flight/Libraries/inc/sanitycheck.h @@ -26,9 +26,17 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include + #ifndef SANITYCHECK_H #define SANITYCHECK_H +#define SANITYCHECK_STATUS_ERROR_NONE SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE +#define SANITYCHECK_STATUS_ERROR_FLIGHTMODE SYSTEMALARMS_EXTENDEDALARMSTATUS_FLIGHTMODE + +#define BOOTFAULT_STATUS_ERROR_NONE SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE +#define BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED + #if (SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM != SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM) || \ (SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM > SYSTEMALARMS_ALARM_NUMELEM) #error Incongruent SystemAlarms. Please revise the UAVO definition in systemalarms.xml diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 07940d764..75c1fd6b2 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -35,7 +35,6 @@ // UAVOs #include -#include #include /**************************** From 8011a9476d26f3dada48778d14d3906ddf1d22fa Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sat, 20 Apr 2013 15:24:12 +0200 Subject: [PATCH 34/34] OP-886 fixed a bug caused by wrong check for xSemaphoreTakeRecursive return code Conflicts: flight/Libraries/alarms.c --- flight/Libraries/alarms.c | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/flight/Libraries/alarms.c b/flight/Libraries/alarms.c index b3706ba24..78238a3bf 100644 --- a/flight/Libraries/alarms.c +++ b/flight/Libraries/alarms.c @@ -70,9 +70,7 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity } // Lock - if (xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0) { - return -1; - } + xSemaphoreTakeRecursive(lock, portMAX_DELAY); // Read alarm and update its severity only if it was changed SystemAlarmsGet(&alarms); @@ -108,9 +106,7 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, } // Lock - if (xSemaphoreTakeRecursive(lock, portMAX_DELAY) != 0) { - return -1; - } + xSemaphoreTakeRecursive(lock, portMAX_DELAY); // Read alarm and update its severity only if it was changed SystemAlarmsGet(&alarms);