Commit 5116e077 authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'Mavlink/master' into orbitOnGuidedBar

* Mavlink/master:
  Parameter search is now typedown style
  Prevent multiple clicks on dialog buttons
  Deploy OpenSSL lib
  Fix trailing slash
  Switch to exact conversion constants
  Copy files in right place
  Add missing headers
  Hack out dynamic font sizing
  Use new polygon drawing tool
  FlightMap supports generic polygon drawing tool
parents b7e6281a d937bd2b
......@@ -63,7 +63,8 @@ WindowsBuild {
ReleaseBuild: DLL_QT_DEBUGCHAR = ""
COPY_FILE_LIST = \
$$BASEDIR\\libs\\lib\\sdl\\win32\\SDL.dll \
$$BASEDIR\\libs\\thirdParty\\libxbee\\lib\\libxbee.dll
$$BASEDIR\\libs\\thirdParty\\libxbee\\lib\\libxbee.dll \
$$BASEDIR\\deploy\\libeay32.dll
for(COPY_FILE, COPY_FILE_LIST) {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$COPY_FILE\" \"$$DESTDIR_WIN\"
......
......@@ -17,10 +17,22 @@
#include "QGroundControlQmlGlobal.h"
#include <QDebug>
#include <QtMath>
#include <limits>
#include <cmath>
// Conversion Constants
// Time
const qreal FactMetaData::UnitConsts_s::secondsPerHour = 3600.0;
// Velocity
const qreal FactMetaData::UnitConsts_s::knotsToKPH = 1.852; // exact, hence weird base for knotsToMetersPerSecond
// Length
const qreal FactMetaData::UnitConsts_s::milesToMeters = 1609.344;
const qreal FactMetaData::UnitConsts_s::feetToMeters = 0.3048;
// Built in translations for all Facts
const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuiltInTranslations[] = {
{ "centi-degrees", "deg", FactMetaData::_centiDegreesToDegrees, FactMetaData::_degreesToCentiDegrees },
......@@ -379,62 +391,62 @@ void FactMetaData::setBuiltInTranslator(void)
QVariant FactMetaData::_degreesToRadians(const QVariant& degrees)
{
return QVariant(degrees.toDouble() * (M_PI / 180.0));
return QVariant(qDegreesToRadians(degrees.toDouble()));
}
QVariant FactMetaData::_radiansToDegrees(const QVariant& radians)
{
return QVariant(radians.toDouble() * (180 / M_PI));
return QVariant(qRadiansToDegrees(radians.toDouble()));
}
QVariant FactMetaData::_centiDegreesToDegrees(const QVariant& centiDegrees)
{
return QVariant(centiDegrees.toFloat() / 100.0f);
return QVariant(centiDegrees.toReal() / 100.0);
}
QVariant FactMetaData::_degreesToCentiDegrees(const QVariant& degrees)
{
return QVariant((unsigned int)(degrees.toFloat() * 100.0f));
return QVariant(qRound(degrees.toReal() * 100.0));
}
QVariant FactMetaData::_metersToFeet(const QVariant& meters)
{
return QVariant(meters.toDouble() * 3.28083989501);
return QVariant(meters.toDouble() * 1.0/constants.feetToMeters);
}
QVariant FactMetaData::_feetToMeters(const QVariant& feet)
{
return QVariant(feet.toDouble() * 0.305);
return QVariant(feet.toDouble() * constants.feetToMeters);
}
QVariant FactMetaData::_metersPerSecondToMilesPerHour(const QVariant& metersPerSecond)
{
return QVariant((metersPerSecond.toDouble() * 0.000621371192) * 60.0 * 60.0);
return QVariant((metersPerSecond.toDouble() * 1.0/constants.milesToMeters) * constants.secondsPerHour);
}
QVariant FactMetaData::_milesPerHourToMetersPerSecond(const QVariant& milesPerHour)
{
return QVariant((milesPerHour.toDouble() * 1609.344) / (60.0 * 60.0));
return QVariant((milesPerHour.toDouble() * constants.milesToMeters) / constants.secondsPerHour);
}
QVariant FactMetaData::_metersPerSecondToKilometersPerHour(const QVariant& metersPerSecond)
{
return QVariant((metersPerSecond.toDouble() / 1000.0) * 60.0 * 60.0);
return QVariant((metersPerSecond.toDouble() / 1000.0) * constants.secondsPerHour);
}
QVariant FactMetaData::_kilometersPerHourToMetersPerSecond(const QVariant& kilometersPerHour)
{
return QVariant((kilometersPerHour.toDouble() * 1000.0) / (60.0 * 60.0));
return QVariant((kilometersPerHour.toDouble() * 1000.0) / constants.secondsPerHour);
}
QVariant FactMetaData::_metersPerSecondToKnots(const QVariant& metersPerSecond)
{
return QVariant(metersPerSecond.toDouble() * 1.94384449244);
return QVariant(metersPerSecond.toDouble() * constants.secondsPerHour / (1000.0 * constants.knotsToKPH));
}
QVariant FactMetaData::_knotsToMetersPerSecond(const QVariant& knots)
{
return QVariant(knots.toDouble() * 0.51444444444);
return QVariant(knots.toDouble() * (constants.knotsToKPH / (1000.0 * constants.secondsPerHour)));
}
QVariant FactMetaData::_percentToNorm(const QVariant& percent)
......
......@@ -188,6 +188,14 @@ private:
bool _rebootRequired;
double _increment;
// Exact conversion constants
static const struct UnitConsts_s {
static const qreal secondsPerHour;
static const qreal knotsToKPH;
static const qreal milesToMeters;
static const qreal feetToMeters;
} constants;
struct BuiltInTranslation_s {
const char* rawUnits;
const char* cookedUnits;
......@@ -195,6 +203,7 @@ private:
Translator cookedTranslator;
};
static const BuiltInTranslation_s _rgBuiltInTranslations[];
static const AppSettingsTranslation_s _rgAppSettingsTranslations[];
......
......@@ -128,4 +128,152 @@ Map {
label: "Q"
}
}
//---- Polygon drawing code
//
// Usage:
//
// Connections {
// target: map.polygonDraw
//
// onPolygonStarted: {
// // Polygon creation has started
// }
//
// onPolygonFinished: {
// // Polygon capture complete, coordinates signal variable contains the polygon points
// }
// }
//
// map.polygonDraqw.startPolgyon() - begin capturing a new polygon
// map.polygonDraqw.endPolygon() - end capture (right-click will also end capture)
// Not sure why this is needed, but trying to reference polygonDrawer directly from other code doesn't work
property alias polygonDraw: polygonDrawer
QGCLabel {
id: polygonHelp
anchors.topMargin: parent.height - ScreenTools.availableHeight
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
horizontalAlignment: Text.AlignHCenter
text: qsTr("Click to add point %1").arg(ScreenTools.isMobile || !polygonDrawer.polygonReady ? "" : qsTr("- Right Click to end polygon"))
visible: polygonDrawer.drawingPolygon
}
MouseArea {
id: polygonDrawer
anchors.fill: parent
acceptedButtons: Qt.LeftButton | Qt.RightButton
visible: drawingPolygon
z: 1000 // Hack to fix MouseArea layering for now
property alias drawingPolygon: polygonDrawer.hoverEnabled
property bool polygonReady: polygonDrawerPolygon.path.length > 3 ///< true: enough points have been captured to create a closed polygon
/// New polygon capture has started
signal polygonStarted
/// Polygon capture is complete
/// @param coordinates Map coordinates for the polygon points
signal polygonFinished(var coordinates)
/// Begin capturing a new polygon
/// polygonStarted will be signalled
function startPolygon() {
polygonDrawer.drawingPolygon = true
polygonDrawer._clearPolygon()
polygonDrawer.polygonStarted()
}
/// Finish capturing the polygon
/// polygonFinished will be signalled
/// @return true: polygon completed, false: not enough points to complete polygon
function finishPolygon() {
if (!polygonDrawer.polygonReady) {
return false
}
var polygonPath = polygonDrawerPolygon.path
polygonPath.pop() // get rid of drag coordinate
polygonDrawer._clearPolygon()
polygonDrawer.drawingPolygon = false
polygonDrawer.polygonFinished(polygonPath)
return true
}
function _clearPolygon() {
// Simpler methods to clear the path simply don't work due to bugs. This craziness does.
var bogusCoord = _map.toCoordinate(Qt.point(height/2, width/2))
polygonDrawerPolygon.path = [ bogusCoord, bogusCoord ]
polygonDrawerNextPoint.path = [ bogusCoord, bogusCoord ]
polygonDrawerPolygon.path = [ ]
polygonDrawerNextPoint.path = [ ]
}
onClicked: {
if (mouse.button == Qt.LeftButton) {
if (polygonDrawerPolygon.path.length > 2) {
// Make sure the new line doesn't intersect the existing polygon
var lastSegment = polygonDrawerPolygon.path.length - 2
var newLineA = _map.fromCoordinate(polygonDrawerPolygon.path[lastSegment], false /* clipToViewPort */)
var newLineB = _map.fromCoordinate(polygonDrawerPolygon.path[lastSegment+1], false /* clipToViewPort */)
for (var i=0; i<lastSegment; i++) {
var oldLineA = _map.fromCoordinate(polygonDrawerPolygon.path[i], false /* clipToViewPort */)
var oldLineB = _map.fromCoordinate(polygonDrawerPolygon.path[i+1], false /* clipToViewPort */)
if (QGroundControl.linesIntersect(newLineA, newLineB, oldLineA, oldLineB)) {
return;
}
}
}
var clickCoordinate = _map.toCoordinate(Qt.point(mouse.x, mouse.y))
var polygonPath = polygonDrawerPolygon.path
if (polygonPath.length == 0) {
// Add first coordinate
polygonPath.push(clickCoordinate)
} else {
// Update finalized coordinate
polygonPath[polygonDrawerPolygon.path.length - 1] = clickCoordinate
}
// Add next drag coordinate
polygonPath.push(clickCoordinate)
polygonDrawerPolygon.path = polygonPath
} else if (polygonDrawer.polygonReady) {
finishPolygon()
}
}
onPositionChanged: {
if (polygonDrawerPolygon.path.length) {
var dragCoordinate = _map.toCoordinate(Qt.point(mouse.x, mouse.y))
// Update drag line
polygonDrawerNextPoint.path = [ polygonDrawerPolygon.path[polygonDrawerPolygon.path.length - 2], dragCoordinate ]
// Update drag coordinate
var polygonPath = polygonDrawerPolygon.path
polygonPath[polygonDrawerPolygon.path.length - 1] = dragCoordinate
polygonDrawerPolygon.path = polygonPath
}
}
}
MapPolygon {
id: polygonDrawerPolygon
color: "blue"
opacity: 0.5
visible: polygonDrawer.drawingPolygon
}
MapPolyline {
id: polygonDrawerNextPoint
line.color: "green"
line.width: 5
visible: polygonDrawer.drawingPolygon
}
//---- End Polygon Drawing code
} // Map
......@@ -19,8 +19,7 @@ Rectangle {
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
property bool _addPointsMode: false
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _margin: ScreenTools.defaultFontPixelWidth / 2
QGCPalette { id: qgcPal; colorGroupEnabled: true }
......@@ -32,16 +31,6 @@ Rectangle {
anchors.right: parent.right
spacing: _margin
Connections {
target: editorMap
onMapClicked: {
if (_addPointsMode) {
missionItem.addPolygonCoordinate(coordinate)
}
}
}
QGCLabel {
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
......@@ -109,14 +98,29 @@ Rectangle {
}
}
Connections {
target: editorMap.polygonDraw
onPolygonStarted: {
missionItem.clearPolygon()
}
onPolygonFinished: {
for (var i=0; i<coordinates.length; i++) {
missionItem.addPolygonCoordinate(coordinates[i])
}
}
}
QGCButton {
text: _addPointsMode ? qsTr("Finish Polygon") : qsTr("Draw Polygon")
text: editorMap.polygonDraw.drawingPolygon ? qsTr("Finish Polygon") : qsTr("Draw Polygon")
enabled: (editorMap.polygonDraw.drawingPolygon && editorMap.polygonDraw.polygonReady) || !editorMap.polygonDraw.drawingPolygon
onClicked: {
if (_addPointsMode) {
_addPointsMode = false
if (editorMap.polygonDraw.drawingPolygon) {
editorMap.polygonDraw.finishPolygon()
} else {
missionItem.clearPolygon()
_addPointsMode = true
editorMap.polygonDraw.startPolygon()
}
}
}
......
......@@ -32,9 +32,8 @@ QGCView {
property Fact _editorDialogFact: Fact { }
property int _rowHeight: ScreenTools.defaultFontPixelHeight * 2
property int _rowWidth: 10 // Dynamic adjusted at runtime
property bool _searchFilter: false ///< true: showing results of search
property bool _searchFilter: searchText.text != "" ///< true: showing results of search
property var _searchResults ///< List of parameter names from search results
property string _currentGroup: ""
property bool _showRCToParam: !ScreenTools.isMobile && QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
ParameterEditorController {
......@@ -55,34 +54,24 @@ QGCView {
id: header
anchors.left: parent.left
anchors.right: parent.right
height: searchText.height + ScreenTools.defaultFontPixelHeight / 3
spacing: ScreenTools.defaultFontPixelWidth
QGCTextField {
id: searchText
QGCLabel {
anchors.baseline: clearButton.baseline
text: qsTr("Search:")
}
QGCButton {
anchors.top: searchText.top
anchors.bottom: searchText.bottom
text: qsTr("Search")
onClicked: {
_searchResults = controller.searchParametersForComponent(-1, searchText.text)
_searchFilter = true
}
QGCTextField {
id: searchText
anchors.baseline: clearButton.baseline
text: controller.searchText
onDisplayTextChanged: controller.searchText = displayText
}
QGCButton {
anchors.top: searchText.top
anchors.bottom: searchText.bottom
text: qsTr("Clear")
visible: _searchFilter
onClicked: {
searchText.text = ""
_searchFilter = false
hideDialog()
}
id: clearButton
text: qsTr("Clear")
onClicked: searchText.text = ""
}
} // Row - Header
......@@ -132,184 +121,135 @@ QGCView {
}
}
//---------------------------------------------
//-- Contents
Loader {
anchors.left: parent.left
anchors.right: parent.right
/// Group buttons
QGCFlickable {
id : groupScroll
width: ScreenTools.defaultFontPixelWidth * 25
anchors.top: header.bottom
anchors.bottom: parent.bottom
sourceComponent: _searchFilter ? searchResultsViewComponent: groupedViewComponent
}
}
clip: true
pixelAligned: true
contentHeight: groupedViewComponentColumn.height
contentWidth: groupedViewComponentColumn.width
flickableDirection: Flickable.VerticalFlick
visible: !_searchFilter
//-- Parameter Groups
Component {
id: groupedViewComponent
Row {
spacing: ScreenTools.defaultFontPixelWidth * 0.5
//-- Parameter Groups
QGCFlickable {
id : groupScroll
width: ScreenTools.defaultFontPixelWidth * 25
height: parent.height
clip: true
pixelAligned: true
contentHeight: groupedViewComponentColumn.height
contentWidth: groupedViewComponentColumn.width
flickableDirection: Flickable.VerticalFlick
Column {
id: groupedViewComponentColumn
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
Repeater {
model: controller.componentIds
Column {
id: componentColumn
readonly property int componentId: parseInt(modelData)
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
QGCLabel {
text: qsTr("Component #: %1").arg(componentId.toString())
font.family: ScreenTools.demiboldFontFamily
anchors.horizontalCenter: parent.horizontalCenter
}
ExclusiveGroup { id: groupGroup }
Repeater {
model: controller.getGroupsForComponent(componentId)
QGCButton {
width: ScreenTools.defaultFontPixelWidth * 25
text: modelData
height: _rowHeight
exclusiveGroup: setupButtonGroup
onClicked: {
checked = true
// Clear the rows from the component first. This allows us to change the componentId without
// breaking any bindings.
factRowsLoader.parameterNames = [ ]
_rowWidth = 10
factRowsLoader.componentId = componentId
factRowsLoader.parameterNames = controller.getParametersForGroup(componentId, modelData)
_currentGroup = modelData
factScrollView.contentX = 0
factScrollView.contentY = 0
}
Column {
id: groupedViewComponentColumn
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
Repeater {
model: controller.componentIds
Column {
id: componentColumn
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
readonly property int componentId: modelData
QGCLabel {
text: qsTr("Component #: %1").arg(componentId.toString())
font.family: ScreenTools.demiboldFontFamily
anchors.horizontalCenter: parent.horizontalCenter
}
ExclusiveGroup { id: groupGroup }
Repeater {
model: controller.getGroupsForComponent(componentId)
QGCButton {
width: ScreenTools.defaultFontPixelWidth * 25
text: groupName
height: _rowHeight
exclusiveGroup: setupButtonGroup
readonly property string groupName: modelData
onClicked: {
checked = true
_rowWidth = 10
controller.currentComponentId = componentId
controller.currentGroup = groupName
}
}
}
}
}
}
Rectangle {
color: __qgcPal.text
width: 1
height: parent.height
opacity: 0.1
}
//-- Parameters
QGCFlickable {
id: factScrollView
width: parent.width - groupScroll.width
height: parent.height
contentHeight: factRowsLoader.height
contentWidth: _rowWidth
boundsBehavior: Flickable.OvershootBounds
pixelAligned: true
clip: true
Loader {
id: factRowsLoader
sourceComponent: factRowsComponent
property int componentId: controller.componentIds[0]
property var parameterNames: controller.getParametersForGroup(componentId, controller.getGroupsForComponent(componentId)[0])
onLoaded: {
_currentGroup = controller.getGroupsForComponent(controller.componentIds[0])[0]
}
}
}
}
}
//---------------------------------------------
// Search result view
Component {
id: searchResultsViewComponent
Item {
QGCFlickable {
id: factScrollView
width: parent.width
height: parent.height
contentHeight: factRowsLoader.height
contentWidth: _rowWidth
boundsBehavior: Flickable.OvershootBounds
pixelAligned: true
clip: true
Loader {
id: factRowsLoader
sourceComponent: factRowsComponent
property int componentId: -1
property var parameterNames: _searchResults
}
}
}
}
/// Parameter list
ListView {
id: editorListView
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: _searchFilter ? parent.left : groupScroll.right
anchors.right: parent.right
anchors.top: header.bottom
anchors.bottom: parent.bottom
orientation: ListView.Vertical
model: controller.parameters
cacheBuffer: height > 0 ? height * 2 : 0
clip: true
delegate: Rectangle {
height: _rowHeight
width: _rowWidth
color: Qt.rgba(0,0,0,0)
Row {
id: factRow
spacing: Math.ceil(ScreenTools.defaultFontPixelWidth * 0.5)
anchors.verticalCenter: parent.verticalCenter
property Fact modelFact: object
QGCLabel {
id: nameLabel
width: ScreenTools.defaultFontPixelWidth * 20
text: factRow.modelFact.name
clip: true
}
//---------------------------------------------
// Paremeters view
Component {
id: factRowsComponent
Column {
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
Repeater {
model: parameterNames
Rectangle {
height: _rowHeight
width: _rowWidth
color: Qt.rgba(0,0,0,0)
Row {
id: factRow
property Fact modelFact: controller.getParameterFact(componentId, modelData)
spacing: Math.ceil(ScreenTools.defaultFontPixelWidth * 0.5)
anchors.verticalCenter: parent.verticalCenter
QGCLabel {
id: nameLabel
width: ScreenTools.defaultFontPixelWidth * 20
text: factRow.modelFact.name
clip: true
}
QGCLabel {
id: valueLabel
width: ScreenTools.defaultFontPixelWidth * 20
color: factRow.modelFact.defaultValueAvailable ? (factRow.modelFact.valueEqualsDefault ? __qgcPal.text : __qgcPal.warningText) : __qgcPal.text
text: factRow.modelFact.enumStrings.length == 0 ? factRow.modelFact.valueString + " " + factRow.modelFact.units : factRow.modelFact.enumStringValue
clip: true
}
QGCLabel {
text: factRow.modelFact.shortDescription
}
Component.onCompleted: {
if(_rowWidth < factRow.width + ScreenTools.defaultFontPixelWidth) {
_rowWidth = factRow.width + ScreenTools.defaultFontPixelWidth
}
}
QGCLabel {
id: valueLabel
width: ScreenTools.defaultFontPixelWidth * 20
color: factRow.modelFact.defaultValueAvailable ? (factRow.modelFact.valueEqualsDefault ? __qgcPal.text : __qgcPal.warningText) : __qgcPal.text
text: factRow.modelFact.enumStrings.length == 0 ? factRow.modelFact.valueString + " " + factRow.modelFact.units : factRow.modelFact.enumStringValue
clip: true
}
Rectangle {
width: _rowWidth
height: 1
color: __qgcPal.text
opacity: 0.15
anchors.bottom: parent.bottom
anchors.left: parent.left
QGCLabel {
text: factRow.modelFact.shortDescription
}
MouseArea {
anchors.fill: parent
acceptedButtons: Qt.LeftButton
onClicked: {
_editorDialogFact = factRow.modelFact
showDialog(editorDialogComponent, qsTr("Parameter Editor"), qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Save)
Component.onCompleted: {
if(_rowWidth < factRow.width + ScreenTools.defaultFontPixelWidth) {
_rowWidth = factRow.width + ScreenTools.defaultFontPixelWidth
}
}
}
Rectangle {
width: _rowWidth
height: 1
color: __qgcPal.text
opacity: 0.15
anchors.bottom: parent.bottom
anchors.left: parent.left
}
MouseArea {
anchors.fill: parent
acceptedButtons: Qt.LeftButton
onClicked: {
_editorDialogFact = factRow.modelFact
showDialog(editorDialogComponent, qsTr("Parameter Editor"), qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Save)
}
}
}
}
}
} // QGCViewPanel
Component {
id: editorDialogComponent
......@@ -320,44 +260,6 @@ QGCView {
}
}
Component {
id: searchDialogComponent
QGCViewDialog {
function accept() {
_searchResults = controller.searchParametersForComponent(-1, searchFor.text, true /*searchInName.checked*/, true /*searchInDescriptions.checked*/)
_searchFilter = true
hideDialog()
}
function reject() {
_searchFilter = false
hideDialog()
}
QGCLabel {
id: searchForLabel
text: qsTr("Search for:")
}
QGCTextField {
id: searchFor
anchors.topMargin: defaultTextHeight / 3
anchors.top: searchForLabel.bottom
width: ScreenTools.defaultFontPixelWidth * 20
}
QGCLabel {
anchors.topMargin: defaultTextHeight
anchors.top: searchFor.bottom
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Hint: Leave 'Search For' blank and click Apply to list all parameters sorted by name.")
}
}
}
Component {
id: mobileFilePicker
......
......@@ -25,14 +25,20 @@
/// @Brief Constructs a new ParameterEditorController Widget. This widget is used within the PX4VehicleConfig set of screens.
ParameterEditorController::ParameterEditorController(void)
: _currentComponentId(_vehicle->defaultComponentId())
, _parameters(new QmlObjectListModel(this))
{
if (_autopilot) {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
foreach (int componentId, groupMap.keys()) {
_componentIds += QString("%1").arg(componentId);
}
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
foreach (int componentId, groupMap.keys()) {
_componentIds += QString("%1").arg(componentId);
}
_currentGroup = groupMap[_currentComponentId].keys()[0];
_updateParameters();
connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_updateParameters);
connect(this, &ParameterEditorController::currentComponentIdChanged, this, &ParameterEditorController::_updateParameters);
connect(this, &ParameterEditorController::currentGroupChanged, this, &ParameterEditorController::_updateParameters);
}
ParameterEditorController::~ParameterEditorController()
......@@ -42,16 +48,16 @@ ParameterEditorController::~ParameterEditorController()
QStringList ParameterEditorController::getGroupsForComponent(int componentId)
{
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
return groupMap[componentId].keys();
return groupMap[componentId].keys();
}
QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group)
{
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
return groupMap[componentId][group];
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
return groupMap[componentId][group];
}
QStringList ParameterEditorController::searchParametersForComponent(int componentId, const QString& searchText, bool searchInName, bool searchInDescriptions)
......@@ -78,8 +84,8 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen
void ParameterEditorController::clearRCToParam(void)
{
Q_ASSERT(_uas);
_uas->unsetRCToParameterMap();
Q_ASSERT(_uas);
_uas->unsetRCToParameterMap();
}
void ParameterEditorController::saveToFile(const QString& filename)
......@@ -92,15 +98,15 @@ void ParameterEditorController::saveToFile(const QString& filename)
if (!filename.isEmpty()) {
QFile file(filename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
qgcApp()->showMessage(QString("Unable to create file: %1").arg(filename));
return;
}
return;
}
QTextStream stream(&file);
_autopilot->writeParametersToStream(stream);
file.close();
}
QTextStream stream(&file);
_autopilot->writeParametersToStream(stream);
file.close();
}
}
void ParameterEditorController::saveToFilePicker(void)
......@@ -156,7 +162,7 @@ void ParameterEditorController::loadFromFilePicker(void)
void ParameterEditorController::refresh(void)
{
_autopilot->refreshAllParameters();
_autopilot->refreshAllParameters();
}
void ParameterEditorController::resetAllToDefaults(void)
......@@ -170,8 +176,31 @@ void ParameterEditorController::setRCToParam(const QString& paramName)
#ifdef __mobile__
Q_UNUSED(paramName)
#else
Q_ASSERT(_uas);
Q_ASSERT(_uas);
QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(paramName, _uas, qgcApp()->toolbox()->multiVehicleManager(), MainWindow::instance());
d->exec();
d->exec();
#endif
}
void ParameterEditorController::_updateParameters(void)
{
QObjectList newParameterList;
if (_searchText.isEmpty()) {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) {
newParameterList.append(_autopilot->getParameterFact(_currentComponentId, parameter));
}
} else {
foreach(const QString &parameter, _autopilot->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _autopilot->getParameterFact(_vehicle->defaultComponentId(), parameter);
if (fact->name().contains(_searchText, Qt::CaseInsensitive) ||
fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) ||
fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) {
newParameterList.append(fact);
}
}
}
_parameters->swapObjectList(newParameterList);
}
......@@ -20,6 +20,7 @@
#include "AutoPilotPlugin.h"
#include "UASInterface.h"
#include "FactPanelController.h"
#include "QmlObjectListModel.h"
class ParameterEditorController : public FactPanelController
{
......@@ -29,7 +30,11 @@ public:
ParameterEditorController(void);
~ParameterEditorController();
Q_PROPERTY(QStringList componentIds MEMBER _componentIds CONSTANT)
Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged)
Q_PROPERTY(int currentComponentId MEMBER _currentComponentId NOTIFY currentComponentIdChanged)
Q_PROPERTY(QString currentGroup MEMBER _currentGroup NOTIFY currentGroupChanged)
Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters CONSTANT)
Q_PROPERTY(QVariantList componentIds MEMBER _componentIds CONSTANT)
Q_INVOKABLE QStringList getGroupsForComponent(int componentId);
Q_INVOKABLE QStringList getParametersForGroup(int componentId, QString group);
......@@ -47,10 +52,20 @@ public:
QList<QObject*> model(void);
signals:
void searchTextChanged(QString searchText);
void currentComponentIdChanged(int componentId);
void currentGroupChanged(QString group);
void showErrorMessage(const QString& errorMsg);
private slots:
void _updateParameters(void);
private:
QStringList _componentIds;
QVariantList _componentIds;
QString _searchText;
int _currentComponentId;
QString _currentGroup;
QmlObjectListModel* _parameters;
};
#endif
......@@ -123,6 +123,9 @@ FactPanel {
return
}
__rejectButton.enabled = true
__acceptButton.enabled = true
__stopAllAnimations()
__dialogCharWidth = charWidth
......@@ -144,6 +147,9 @@ FactPanel {
return
}
__rejectButton.enabled = true
__acceptButton.enabled = true
__stopAllAnimations()
__dialogCharWidth = showDialogDefaultWidth
......@@ -302,7 +308,10 @@ FactPanel {
anchors.right: __acceptButton.visible ? __acceptButton.left : parent.right
anchors.bottom: parent.bottom
onClicked: __dialogComponentLoader.item.reject()
onClicked: {
enabled = false // prevent multiple clicks
__dialogComponentLoader.item.reject()
}
}
QGCButton {
......@@ -311,6 +320,7 @@ FactPanel {
primary: true
onClicked: {
enabled = false // prevent multiple clicks
__dialogComponentLoader.item.accept()
}
}
......
......@@ -14,6 +14,8 @@
#include "QGroundControlQmlGlobal.h"
#include <QSettings>
#include <QLineF>
#include <QPointF>
static const char* kQmlGlobalKeyName = "QGCQml";
......@@ -264,3 +266,11 @@ Fact* QGroundControlQmlGlobal::speedUnits(void)
return _speedUnitsFact;
}
bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B)
{
QPointF intersectPoint;
return QLineF(line1A, line1B).intersect(QLineF(line2A, line2B), &intersectPoint) == QLineF::BoundedIntersection &&
intersectPoint != line1A && intersectPoint != line1B;
}
......@@ -130,6 +130,8 @@ public:
/// Updates the logging filter rules after settings have changed
Q_INVOKABLE void updateLoggingFilterRules(void) { QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(QString()); }
Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2);
// Property accesors
FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
......
......@@ -179,7 +179,7 @@ void QmlObjectListModel::append(QObject* object)
insert(_objectList.count(), object);
}
QObjectList QmlObjectListModel::swapObjectList(QObjectList newlist)
QObjectList QmlObjectListModel::swapObjectList(const QObjectList& newlist)
{
QObjectList oldlist(_objectList);
beginResetModel();
......
......@@ -37,7 +37,7 @@ public:
void setDirty(bool dirty);
void append(QObject* object);
QObjectList swapObjectList(QObjectList newlist);
QObjectList swapObjectList(const QObjectList& newlist);
void clear(void);
QObject* removeAt(int i);
QObject* removeOne(QObject* object) { return removeAt(indexOf(object)); }
......
......@@ -57,28 +57,24 @@ LinuxBuild {
$$GST_ROOT/include/gstreamer-1.0 \
$$GST_ROOT/include/glib-2.0 \
$$GST_ROOT/lib/gstreamer-1.0/include \
$$GST_ROOT/lib/glib-2.0/include
}
COPY_FILE_LIST = \
$$GST_ROOT\\bin\\libffi-6.dll \
$$GST_ROOT\\bin\\libglib-2.0-0.dll \
$$GST_ROOT\\bin\\libgmodule-2.0-0.dll \
$$GST_ROOT\\bin\\libgobject-2.0-0.dll \
$$GST_ROOT\\bin\\libgstbase-1.0-0.dll \
$$GST_ROOT\\bin\\libgstreamer-1.0-0.dll \
$$GST_ROOT\\bin\\libgstvideo-1.0-0.dll \
$$GST_ROOT\\bin\\libintl-8.dll \
$$GST_ROOT\\bin\\liborc-0.4-0.dll \
$$GST_ROOT\\bin\\libwinpthread-1.dll \
DESTDIR_WIN = $$replace(DESTDIR, "/", "\\")
for(COPY_FILE, COPY_FILE_LIST) {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$COPY_FILE\" \"$$DESTDIR_WIN\"
$$GST_ROOT/lib/glib-2.0/include
COPY_FILE_LIST = \
$$GST_ROOT\\bin\\libffi-6.dll \
$$GST_ROOT\\bin\\libglib-2.0-0.dll \
$$GST_ROOT\\bin\\libgmodule-2.0-0.dll \
$$GST_ROOT\\bin\\libgobject-2.0-0.dll \
$$GST_ROOT\\bin\\libgstbase-1.0-0.dll \
$$GST_ROOT\\bin\\libgstreamer-1.0-0.dll \
$$GST_ROOT\\bin\\libgstvideo-1.0-0.dll \
$$GST_ROOT\\bin\\libintl-8.dll \
$$GST_ROOT\\bin\\liborc-0.4-0.dll \
$$GST_ROOT\\bin\\libwinpthread-1.dll
DESTDIR_WIN = $$replace(DESTDIR, "/", "\\")
for(COPY_FILE, COPY_FILE_LIST) {
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$COPY_FILE\" \"$$DESTDIR_WIN\"
}
QMAKE_POST_LINK += $$escape_expand(\\n)
}
QMAKE_POST_LINK += $$escape_expand(\\n)
} else:AndroidBuild {
#- gstreamer assumed to be installed in $$PWD/../../android/gstreamer-1.0-android-armv7-1.5.2
GST_ROOT = $$PWD/../../gstreamer-1.0-android-armv7-1.5.2
......
......@@ -199,6 +199,7 @@ void UASQuickView::resizeEvent(QResizeEvent *evt)
}
void UASQuickView::recalculateItemTextSizing()
{
return;
int minpixelsize = 65535;
for (QMap<QString,UASQuickViewItem*>::const_iterator i = uasPropertyToLabelMap.constBegin();i!=uasPropertyToLabelMap.constEnd();i++)
{
......
......@@ -14,7 +14,7 @@ UASQuickViewTextItem::UASQuickViewTextItem(QWidget *parent) : UASQuickViewItem(p
titleLabel->setSizePolicy(QSizePolicy::MinimumExpanding,QSizePolicy::Minimum);
titleLabel->setObjectName(QString::fromUtf8("title"));
QFont titlefont = titleLabel->font();
titlefont.setPixelSize(this->height() / 4.0);
//titlefont.setPixelSize(this->height() / 4.0);
titleLabel->setFont(titlefont);
layout->addWidget(titleLabel);
......@@ -25,7 +25,7 @@ UASQuickViewTextItem::UASQuickViewTextItem(QWidget *parent) : UASQuickViewItem(p
valueLabel->setObjectName(QString::fromUtf8("value"));
valueLabel->setText("0.00");
QFont valuefont = valueLabel->font();
valuefont.setPixelSize(this->height() / 2.0);
//valuefont.setPixelSize(this->height() / 2.0);
valueLabel->setFont(valuefont);
layout->addWidget(valueLabel);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment