Commit 74ff6711 authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'MavLink/master' into flickableInOfflineMaps

* MavLink/master:
  Update fact meta data for PX4
  Add missing header
  Fix binding
  Add mission header
  Add missing header
  ComplexMissionItem support for Survey
  Header re-structuring
  Raise min Qt version to 5.5+

Conflicts:
	src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
parents 03683ca1 e29dce3d
......@@ -99,6 +99,7 @@
<file alias="MapAddMissionBlack.svg">src/FlightMap/Images/MapAddMissionBlack.svg</file>
<file alias="MapCenter.svg">src/FlightMap/Images/MapCenter.svg</file>
<file alias="MapCenterBlack.svg">src/FlightMap/Images/MapCenterBlack.svg</file>
<file alias="MapDrawShape.svg">src/FlightMap/Images/MapDrawShape.svg</file>
<file alias="MapHome.svg">src/FlightMap/Images/MapHome.svg</file>
<file alias="MapHomeBlack.svg">src/FlightMap/Images/MapHomeBlack.svg</file>
<file alias="MapSync.svg">src/FlightMap/Images/MapSync.svg</file>
......
......@@ -23,8 +23,8 @@ exists($${OUT_PWD}/qgroundcontrol.pro) {
message(Qt version $$[QT_VERSION])
!equals(QT_MAJOR_VERSION, 5) | !greaterThan(QT_MINOR_VERSION, 3) {
error("Unsupported Qt version, 5.4+ is required")
!equals(QT_MAJOR_VERSION, 5) | !greaterThan(QT_MINOR_VERSION, 4) {
error("Unsupported Qt version, 5.5+ is required")
}
include(QGCCommon.pri)
......@@ -261,6 +261,8 @@ HEADERS += \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/SimpleMissionItem.h \
src/QGC.h \
src/QGCApplication.h \
src/QGCComboBox.h \
......@@ -388,6 +390,8 @@ SOURCES += \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \
src/QGC.cc \
src/QGCApplication.cc \
src/QGCComboBox.cc \
......
......@@ -34,6 +34,8 @@
#include <QVariant>
#include <QQmlProperty>
#include <QStandardPaths>
#include <QDir>
bool APMAirframeComponentController::_typesRegistered = false;
......
......@@ -226,6 +226,10 @@
<maintainer>Andreas Antener &lt;andreas@uaventure.com&gt;</maintainer>
<type>Quadrotor x</type>
</airframe>
<airframe id="4040" maintainer="Blankered" name="Reaper 500 Quad">
<maintainer>Blankered</maintainer>
<type>Quadrotor x</type>
</airframe>
</airframe_group>
<airframe_group image="Rover" name="Rover">
<airframe id="50001" maintainer="John Doe &lt;john@example.com&gt;" name="Axial Racing AX10">
......
......@@ -720,6 +720,25 @@ velocity</short_desc>
<min>1.0</min>
<unit>SD</unit>
</parameter>
<parameter default="7" name="EKF2_DECL_TYPE" type="INT32">
<short_desc>Integer bitmask controlling handling of magnetic declination. Set bits to in the following positions to enable functions.
0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value.
1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.
2 : Set to true to always use the declination as an observaton when 3-axis magnetometer fusion is being used</short_desc>
<min>0</min>
<max>7</max>
<unit />
</parameter>
<parameter default="0" name="EKF2_MAG_TYPE" type="INT32">
<short_desc>Integer controlling the type of magnetometer fusion used - magnetic heading or 3-axis magnetometer.
0 : determine the best fusion method to use automatically - heading fusion on-ground and 3-axis fusion in-flight
1 : always use magnetic heading fusion
2 : always use 3-axis fusion
Other values will disable magnetometer fusion completely</short_desc>
<min>0</min>
<max>2</max>
<unit>None</unit>
</parameter>
<parameter default="3.0" name="EKF2_BARO_GATE" type="FLOAT">
<short_desc>Gate size for barometric height fusion</short_desc>
<min>1.0</min>
......@@ -1149,6 +1168,12 @@ velocity</short_desc>
<min>0.0</min>
<max>1.0</max>
</parameter>
<parameter default="0.15" name="FW_THR_IDLE" type="FLOAT">
<short_desc>Idle throttle</short_desc>
<long_desc>This is the minimum throttle while on the ground For aircraft with internal combustion engine this parameter should be set above desired idle rpm.</long_desc>
<min>0.0</min>
<max>0.4</max>
</parameter>
<parameter default="1.0" name="FW_THR_LND_MAX" type="FLOAT">
<short_desc>Throttle limit value before flare</short_desc>
<long_desc>This throttle value will be set as throttle limit at FW_LND_TLALT, before arcraft will flare.</long_desc>
......@@ -1265,7 +1290,7 @@ velocity</short_desc>
</parameter>
<parameter default="0.0" name="LAUN_CAT_MDEL" type="FLOAT">
<short_desc>Motor delay</short_desc>
<long_desc>Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to LAUN_THR_PRE, set to 0 to deactivate</long_desc>
<long_desc>Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate</long_desc>
<min>0</min>
<unit>seconds</unit>
</parameter>
......@@ -1276,12 +1301,6 @@ velocity</short_desc>
<max>45</max>
<unit>deg</unit>
</parameter>
<parameter default="0.0" name="LAUN_THR_PRE" type="FLOAT">
<short_desc>Throttle setting while detecting launch</short_desc>
<long_desc>The throttle is set to this value while the system is waiting for the take-off.</long_desc>
<min>0</min>
<max>1</max>
</parameter>
</group>
<group name="Local Position Estimator">
<parameter default="1" name="LPE_ENABLED" type="INT32">
......@@ -1479,6 +1498,17 @@ velocity</short_desc>
<min>0</min>
<max>3</max>
</parameter>
<parameter default="-1.0" name="MIS_YAW_TMT" type="FLOAT">
<short_desc>Time in seconds we wait on reaching target heading at a waypoint if it is forced</short_desc>
<long_desc>If set &gt; 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transiton. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default.</long_desc>
<min>-1</min>
<max>20</max>
</parameter>
<parameter default="12.0" name="MIS_YAW_ERR" type="FLOAT">
<short_desc>Max yaw error in degree needed for waypoint heading acceptance</short_desc>
<min>0</min>
<max>90</max>
</parameter>
<parameter default="50.0" name="NAV_LOITER_RAD" type="FLOAT">
<short_desc>Loiter radius (FW only)</short_desc>
<long_desc>Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).</long_desc>
......@@ -1797,6 +1827,24 @@ velocity</short_desc>
<max>1.0</max>
<decimal>3</decimal>
</parameter>
<parameter default="0.5" name="MPC_THR_HOVER" type="FLOAT">
<short_desc>Hover thrust</short_desc>
<long_desc>Vertical thrust required to hover. This value is mapped to center stick for manual throttle control. With this value set to the thrust required to hover, transition from manual to ALTCTL mode while hovering will occur with the throttle stick near center, which is then interpreted as (near) zero demand for vertical speed.</long_desc>
<min>0.2</min>
<max>0.8</max>
</parameter>
<parameter default="0.1" name="MPC_ALTCTL_DZ" type="FLOAT">
<short_desc>ALTCTL throttle curve breakpoint</short_desc>
<long_desc>Halfwidth of deadband or reduced sensitivity center portion of curve. This is the halfwidth of the center region of the ALTCTL throttle curve. It extends from center-dz to center+dz.</long_desc>
<min>0.0</min>
<max>0.2</max>
</parameter>
<parameter default="0.0" name="MPC_ALTCTL_DY" type="FLOAT">
<short_desc>ALTCTL throttle curve breakpoint height</short_desc>
<long_desc>Controls the slope of the reduced sensitivity region. This is the height of the ALTCTL throttle curve at center-dz and center+dz.</long_desc>
<min>0.0</min>
<max>0.2</max>
</parameter>
<parameter default="0.9" name="MPC_THR_MAX" type="FLOAT">
<short_desc>Maximum thrust in auto thrust control</short_desc>
<long_desc>Limit max allowed thrust. Setting a value of one can put the system into actuator saturation as no spread between the motors is possible any more. A value of 0.8 - 0.9 is recommended.</long_desc>
......@@ -1944,13 +1992,6 @@ velocity</short_desc>
<unit>%</unit>
<decimal>2</decimal>
</parameter>
<parameter default="0.1" name="MPC_HOLD_Z_DZ" type="FLOAT">
<short_desc>Deadzone of Z stick where altitude hold is enabled</short_desc>
<min>0.0</min>
<max>1.0</max>
<unit>%</unit>
<decimal>2</decimal>
</parameter>
<parameter default="0.5" name="MPC_HOLD_MAX_XY" type="FLOAT">
<short_desc>Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)</short_desc>
<min>0.0</min>
......@@ -3513,6 +3554,12 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL</short_desc>
<min>0</min>
<max>1</max>
</parameter>
<parameter default="0" name="SDLOG_UTC_OFFSET" type="INT32">
<short_desc>UTC offset (unit: min)</short_desc>
<long_desc>the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets</long_desc>
<min>-1000</min>
<max>1000</max>
</parameter>
</group>
<group name="Sensor Calibration">
<parameter default="0" name="CAL_BOARD_ID" type="INT32">
......@@ -3884,6 +3931,8 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL</short_desc>
<max>921600</max>
<reboot_required>true</reboot_required>
<values>
<value code="357600">Telemetry (57600 baud, 8N1)</value>
<value code="257600">Command Receiver (57600 baud, 8N1)</value>
<value code="57600">Companion Link (57600 baud, 8N1)</value>
<value code="921600">Companion Link (921600 baud, 8N1)</value>
<value code="157600">OSD (57600 baud, 8N1)</value>
......@@ -4041,6 +4090,22 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL</short_desc>
<min>0</min>
<max>1</max>
</parameter>
<parameter default="0" name="VT_WV_LND_EN" type="INT32">
<short_desc>Enable weather-vane mode landings for missions</short_desc>
<min>0</min>
<max>1</max>
</parameter>
<parameter default="0.15" name="VT_WV_YAWR_SCL" type="FLOAT">
<short_desc>Weather-vane yaw rate scale</short_desc>
<long_desc>The desired yawrate from the controller will be scaled in order to avoid yaw fighting against the wind.</long_desc>
<min>0</min>
<max>1</max>
</parameter>
<parameter default="0" name="VT_WV_LTR_EN" type="INT32">
<short_desc>Enable weather-vane mode for loiter</short_desc>
<min>0</min>
<max>1</max>
</parameter>
<parameter default="15.0" name="VT_TRANS_TIMEOUT" type="FLOAT">
<short_desc>Front transition timeout</short_desc>
<long_desc>Time in seconds after which transition will be cancelled. Disabled if set to 0.</long_desc>
......
......@@ -29,6 +29,7 @@
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include <QMutex>
#include <QDir>
#include "FactSystem.h"
#include "MAVLinkProtocol.h"
......
......@@ -32,6 +32,7 @@
#include <QFileInfo>
#include <QDir>
#include <QDebug>
#include <QStack>
QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="-89 46 72 72" enable-background="new -89 46 72 72" xml:space="preserve">
<g transform="matrix(0.96508576,0,0,0.94661676,-1.3508671,3.6129809)">
<path fill="none" stroke="#FFFFFF" stroke-width="1.2" stroke-miterlimit="4" d="m -69.288973,77.48289 22.722433,-9.307985 2.098859,4.288973 -23.726235,9.39924 1.186311,4.471483 23.908746,-9.855514 L -41,80.768061 -66.186312,91.079848 -65,95.551331 l 25.460076,-10.403042 -2.372624,7.391635 -13.140684,5.110266"/>
</g>
<path fill="none" stroke="#FFFFFF" stroke-width="2" stroke-miterlimit="10" d="m -44.193916,62.152091 10.76806,20.623574 -9.21673,19.346005 -24.638783,-3.011404 -6.205323,-25.186312 z"/>
</svg>
......@@ -73,7 +73,7 @@ Rectangle {
id: attitude
y: _topBottomMargin
size: parent.width * 0.95
active: active
active: instrumentPanel.active
anchors.horizontalCenter: parent.horizontalCenter
}
......@@ -112,7 +112,7 @@ Rectangle {
anchors.topMargin: _spacing
anchors.top: _spacer2.bottom
size: parent.width * 0.95
active: active
active: instrumentPanel.active
anchors.horizontalCenter: parent.horizontalCenter
}
}
......@@ -285,6 +285,8 @@ QGCView {
anchors.fill: parent
mapName: "MissionEditor"
signal mapClicked(var coordinate)
readonly property real animationDuration: 500
// Initial map position duplicates Fly view position
......@@ -301,15 +303,15 @@ QGCView {
anchors.fill: parent
onClicked: {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y))
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
if (addMissionItemsButton.checked) {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y))
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
var index = controller.insertMissionItem(coordinate, controller.missionItems.count)
var index = controller.insertSimpleMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index)
} else {
editorMap.zoomLevel = editorMap.maxZoomLevel - 2
editorMap.mapClicked(coordinate)
}
}
}
......@@ -364,7 +366,7 @@ QGCView {
}
}
// Add the mission items to the map
// Add the simple mission items to the map
MapItemView {
model: controller.missionItems
delegate: missionItemComponent
......@@ -421,6 +423,22 @@ QGCView {
}
}
// Add the complex mission items to the map
MapItemView {
model: controller.complexMissionItems
delegate: polygonItemComponent
}
Component {
id: polygonItemComponent
MapPolygon {
color: 'green'
path: object.polygonPath
opacity: 0.5
}
}
// Add lines between waypoints
MissionLineView {
model: controller.waypointLines
......@@ -482,7 +500,7 @@ QGCView {
}
onInsert: {
controller.insertMissionItem(editorMap.center, i)
controller.insertSimpleMissionItem(editorMap.center, i)
setCurrentItem(i)
}
......@@ -522,6 +540,23 @@ QGCView {
z: QGroundControl.zOrderWidgets
}
RoundButton {
id: addShapeButton
buttonImage: "/qmlimages/MapDrawShape.svg"
z: QGroundControl.zOrderWidgets
visible: QGroundControl.experimentalSurvey
onClicked: {
var coordinate = editorMap.center
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
var index = controller.insertComplexMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index)
checked = false
}
}
DropButton {
id: syncButton
dropDirection: dropRight
......
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "ComplexMissionItem.h"
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent)
: MissionItem(vehicle, parent)
{
}
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent)
: MissionItem(vehicle, sequenceNumber, command, frame, param1, param2, param3, param4, param5, param6, param7, autoContinue, isCurrentItem, parent)
{
}
ComplexMissionItem::ComplexMissionItem(const ComplexMissionItem& other, QObject* parent)
: MissionItem(other, parent)
{
}
const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem& other)
{
static_cast<MissionItem&>(*this) = other;
return *this;
}
QVariantList ComplexMissionItem::polygonPath(void)
{
return _polygonPath;
#if 0
QVariantList list;
list << QVariant::fromValue(QGeoCoordinate(-35.362686830000001, 149.16410282999999))
<< QVariant::fromValue(QGeoCoordinate(-35.362660579999996, 149.16606619999999))
<< QVariant::fromValue(QGeoCoordinate(-35.363832989999999, 149.16505769));
return list;
#endif
}
void ComplexMissionItem::clearPolygon(void)
{
_polygonPath.clear();
emit polygonPathChanged();
}
void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
{
_polygonPath << QVariant::fromValue(coordinate);
emit polygonPathChanged();
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef ComplexMissionItem_H
#define ComplexMissionItem_H
#include "MissionItem.h"
class ComplexMissionItem : public MissionItem
{
Q_OBJECT
public:
ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL);
ComplexMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent = NULL);
ComplexMissionItem(const ComplexMissionItem& other, QObject* parent = NULL);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_INVOKABLE void clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
QVariantList polygonPath(void);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return false; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
signals:
void polygonPathChanged(void);
private:
QVariantList _polygonPath;
};
#endif
......@@ -27,6 +27,8 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include <QQmlEngine>
MissionCommands::MissionCommands(QGCApplication* app)
: QGCTool(app)
, _commonMissionCommands(QStringLiteral(":/json/MavCmdInfoCommon.json"))
......
......@@ -27,6 +27,8 @@ This file is part of the QGROUNDCONTROL project
#include "CoordinateVector.h"
#include "FirmwarePlugin.h"
#include "QGCApplication.h"
#include "SimpleMissionItem.h"
#include "ComplexMissionItem.h"
#ifndef __mobile__
#include "QGCFileDialog.h"
......@@ -45,6 +47,7 @@ MissionController::MissionController(QObject *parent)
: QObject(parent)
, _editMode(false)
, _missionItems(NULL)
, _complexMissionItems(NULL)
, _activeVehicle(NULL)
, _autoSync(false)
, _firstItemsFromVehicle(false)
......@@ -124,9 +127,9 @@ void MissionController::sendMissionItems(void)
}
}
int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
{
MissionItem * newItem = new MissionItem(_activeVehicle, this);
MissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count());
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
......@@ -152,6 +155,22 @@ int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
return _missionItems->count() - 1;
}
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
ComplexMissionItem * newItem = new ComplexMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count());
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initMissionItem(newItem);
_missionItems->insert(i, newItem);
_complexMissionItems->append(newItem);
_recalcAll();
return _missionItems->count() - 1;
}
void MissionController::removeMissionItem(int index)
{
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index));
......@@ -218,7 +237,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
return false;
}
MissionItem* item = new MissionItem(_activeVehicle, this);
MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(itemValue.toObject(), errorString)) {
missionItems->append(item);
} else {
......@@ -228,7 +247,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
}
if (json.contains(_jsonPlannedHomePositionKey)) {
MissionItem* item = new MissionItem(_activeVehicle, this);
MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
missionItems->insert(0, item);
......@@ -263,7 +282,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
if (versionOk) {
while (!stream.atEnd()) {
MissionItem* item = new MissionItem(_activeVehicle, this);
MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(stream)) {
missionItems->append(item);
......@@ -612,13 +631,24 @@ void MissionController::_initAllMissionItems(void)
qDebug() << "home item" << homeItem->coordinate();
QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
for (int i=0; i<_missionItems->count(); i++) {
_initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
if (!item->simpleItem()) {
newComplexItems->append(item);
}
_initMissionItem(item);
}
delete _complexMissionItems;
_complexMissionItems = newComplexItems;
_recalcAll();
emit missionItemsChanged();
emit complexMissionItemsChanged();
_missionItems->setDirty(false);
......@@ -773,6 +803,11 @@ QmlObjectListModel* MissionController::missionItems(void)
return _missionItems;
}
QmlObjectListModel* MissionController::complexMissionItems(void)
{
return _complexMissionItems;
}
bool MissionController::_findLastAltitude(double* lastAltitude)
{
bool found = false;
......@@ -831,7 +866,7 @@ double MissionController::_normalizeLon(double lon)
/// Add the home position item to the front of the list
void MissionController::_addPlannedHomePosition(QmlObjectListModel* missionItems, bool addToCenter)
{
MissionItem* homeItem = new MissionItem(_activeVehicle, this);
MissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
missionItems->insert(0, homeItem);
if (missionItems->count() > 1 && addToCenter) {
......
......@@ -29,6 +29,8 @@ This file is part of the QGROUNDCONTROL project
#include "QmlObjectListModel.h"
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "MissionItem.h"
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
......@@ -41,6 +43,7 @@ public:
~MissionController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexMissionItems READ complexMissionItems NOTIFY complexMissionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged)
......@@ -57,11 +60,15 @@ public:
Q_INVOKABLE QStringList getMobileMissionFiles(void);
/// @param i: index to insert at
Q_INVOKABLE int insertMissionItem(QGeoCoordinate coordinate, int i);
Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int i);
/// @param i: index to insert at
Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i);
// Property accessors
QmlObjectListModel* missionItems(void);
QmlObjectListModel* complexMissionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync);
......@@ -69,6 +76,7 @@ public:
signals:
void missionItemsChanged(void);
void complexMissionItemsChanged(void);
void waypointLinesChanged(void);
void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void);
......@@ -111,6 +119,7 @@ private:
private:
bool _editMode;
QmlObjectListModel* _missionItems;
QmlObjectListModel* _complexMissionItems;
QmlObjectListModel _waypointLines;
Vehicle* _activeVehicle;
bool _autoSync;
......
......@@ -137,7 +137,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->insertMissionItem(coordinate, _missionController->missionItems()->count());
_missionController->insertSimpleMissionItem(coordinate, _missionController->missionItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
......@@ -182,7 +182,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->insertMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
// Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
......
......@@ -28,8 +28,6 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h"
#include "JsonHelper.h"
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
const double MissionItem::defaultAltitude = 25.0;
FactMetaData* MissionItem::_altitudeMetaData = NULL;
......@@ -71,22 +69,6 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
};
QDebug operator<<(QDebug dbg, const MissionItem& missionItem)
{
QDebugStateSaver saver(dbg);
dbg.nospace() << "MissionItem(" << missionItem.coordinate() << ")";
return dbg;
}
QDebug operator<<(QDebug dbg, const MissionItem* missionItem)
{
QDebugStateSaver saver(dbg);
dbg.nospace() << "MissionItem(" << missionItem->coordinate() << ")";
return dbg;
}
MissionItem::MissionItem(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
......
......@@ -40,8 +40,7 @@
#include "QmlObjectListModel.h"
#include "MissionCommands.h"
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
// Abstract base class for Simple and Complex MissionItem obejcts.
class MissionItem : public QObject
{
Q_OBJECT
......@@ -77,7 +76,6 @@ public:
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint
Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged)
......@@ -90,6 +88,16 @@ public:
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY commandChanged)
Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
// Mission item has two coordinates associated with them:
// coordinate: This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
// exitCoordinate This is the exit point for a waypoint line coming out of the item. For a SimpleMissionItem this will be the same as
// coordinate. For a ComplexMissionItem it may be different than the entry coordinate.
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged)
/// @return true: SimpleMissionItem, false: ComplexMissionItem
Q_PROPERTY(bool simpleItem READ simpleItem NOTIFY simpleItemChanged)
// These properties are used to display the editing ui
Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY uiModelChanged)
Q_PROPERTY(QmlObjectListModel* comboboxFacts READ comboboxFacts NOTIFY uiModelChanged)
......@@ -179,6 +187,10 @@ public:
static const double defaultAltitude;
// Pure virtuals which must be provides by derived classes
virtual bool simpleItem(void) const = 0;
virtual QGeoCoordinate exitCoordinate(void) const = 0;
public slots:
void setDefaultsForCommand(void);
......@@ -188,6 +200,7 @@ signals:
void azimuthChanged (double azimuth);
void commandChanged (MavlinkQmlSingleton::Qml_MAV_CMD command);
void coordinateChanged (const QGeoCoordinate& coordinate);
void exitCoordinateChanged (const QGeoCoordinate& exitCoordinate);
void dirtyChanged (bool dirty);
void distanceChanged (double distance);
void frameChanged (int frame);
......@@ -198,6 +211,7 @@ signals:
void sequenceNumberChanged (int sequenceNumber);
void uiModelChanged (void);
void showHomePositionChanged (bool showHomePosition);
void simpleItemChanged (bool simpleItem);
private slots:
void _setDirtyFromSignal(void);
......@@ -276,7 +290,4 @@ private:
static const char* _jsonCoordinateKey;
};
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
QDebug operator<<(QDebug dbg, const MissionItem* missionItem);
#endif
......@@ -22,7 +22,7 @@
======================================================================*/
#include "MissionItemTest.h"
#include "MissionItem.h"
#include "SimpleMissionItem.h"
const MissionItemTest::ItemInfo_t MissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
......@@ -184,7 +184,7 @@ void MissionItemTest::_test(void)
void MissionItemTest::_testDefaultValues(void)
{
MissionItem item(NULL /* Vehicle */);
SimpleMissionItem item(NULL /* Vehicle */);
item.setCommand(MAV_CMD_NAV_WAYPOINT);
item.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
......
......@@ -29,6 +29,7 @@
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "QGCApplication.h"
#include "SimpleMissionItem.h"
QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
......@@ -64,7 +65,7 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
int firstIndex = skipFirstItem ? 1 : 0;
for (int i=firstIndex; i<missionItems.count(); i++) {
_missionItems.append(new MissionItem(*qobject_cast<const MissionItem*>(missionItems[i])));
_missionItems.append(new SimpleMissionItem(*qobject_cast<const SimpleMissionItem*>(missionItems[i])));
MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1));
......@@ -252,7 +253,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
_requestItemRetryCount = 0;
_itemIndicesToRead.removeOne(missionItem.seq);
MissionItem* item = new MissionItem(_vehicle,
MissionItem* item = new SimpleMissionItem(_vehicle,
missionItem.seq,
(MAV_CMD)missionItem.command,
(MAV_FRAME)missionItem.frame,
......@@ -432,7 +433,7 @@ QmlObjectListModel* MissionManager::copyMissionItems(void)
QmlObjectListModel* list = new QmlObjectListModel();
for (int i=0; i<_missionItems.count(); i++) {
list->append(new MissionItem(*qobject_cast<const MissionItem*>(_missionItems[i])));
list->append(new SimpleMissionItem(*qobject_cast<const SimpleMissionItem*>(_missionItems[i])));
}
return list;
......
......@@ -24,6 +24,7 @@
#include "MissionManagerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
const MissionManagerTest::TestCase_t MissionManagerTest::_rgTestCases[] = {
{ "0\t0\t3\t16\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 0, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_WAYPOINT, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
......@@ -48,7 +49,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QmlObjectListModel* list = new QmlObjectListModel();
// Editor has a home position item on the front, so we do the same
MissionItem* homeItem = new MissionItem(NULL /* Vehicle */, this);
SimpleMissionItem* homeItem = new SimpleMissionItem(NULL /* Vehicle */, this);
homeItem->setHomePositionSpecialCase(true);
homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
homeItem->setCoordinate(QGeoCoordinate(47.3769, 8.549444, 0));
......@@ -58,7 +59,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
for (size_t i=0; i<_cTestCases; i++) {
const TestCase_t* testCase = &_rgTestCases[i];
MissionItem* item = new MissionItem(NULL /* Vehicle */, list);
SimpleMissionItem* item = new SimpleMissionItem(NULL /* Vehicle */, list);
QTextStream loadStream(testCase->itemStream, QIODevice::ReadOnly);
QVERIFY(item->load(loadStream));
......
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "SimpleMissionItem.h"
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
: MissionItem(vehicle, parent)
{
}
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent)
: MissionItem(vehicle, sequenceNumber, command, frame, param1, param2, param3, param4, param5, param6, param7, autoContinue, isCurrentItem, parent)
{
}
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent)
: MissionItem(other, parent)
{
}
const SimpleMissionItem& SimpleMissionItem::operator=(const SimpleMissionItem& other)
{
static_cast<MissionItem&>(*this) = other;
return *this;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef SimpleMissionItem_H
#define SimpleMissionItem_H
#include "MissionItem.h"
class SimpleMissionItem : public MissionItem
{
Q_OBJECT
public:
SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL);
SimpleMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent = NULL);
SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL);
const SimpleMissionItem& operator=(const SimpleMissionItem& other);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return true; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
private:
};
#endif
......@@ -34,6 +34,7 @@
#include <QApplication>
#include <QTimer>
#include <QQmlApplicationEngine>
#include "LinkConfiguration.h"
#include "LinkManager.h"
......
......@@ -30,7 +30,7 @@
QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
QGCLoggingCategoryRegister* _instance = NULL;
......
......@@ -34,6 +34,7 @@
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
This diff is collapsed.
......@@ -34,6 +34,8 @@
#include "MainWindow.h"
#endif
#include <QStandardPaths>
/// @Brief Constructs a new ParameterEditorController Widget. This widget is used within the PX4VehicleConfig set of screens.
ParameterEditorController::ParameterEditorController(void)
{
......
......@@ -206,3 +206,18 @@ void QGroundControlQmlGlobal::setVirtualTabletJoystick(bool enabled)
emit virtualTabletJoystickChanged(enabled);
}
}
bool QGroundControlQmlGlobal::experimentalSurvey(void) const
{
QSettings settings;
return settings.value("ExperimentalSurvey", false).toBool();
}
void QGroundControlQmlGlobal::setExperimentalSurvey(bool experimentalSurvey)
{
QSettings settings;
settings.setValue("ExperimentalSurvey", experimentalSurvey);
emit experimentalSurveyChanged(experimentalSurvey);
}
......@@ -79,6 +79,9 @@ public:
Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT)
Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged)
/// @ return: true: experimental survey ip code is turned on
Q_PROPERTY(bool experimentalSurvey READ experimentalSurvey WRITE setExperimentalSurvey NOTIFY experimentalSurveyChanged)
Q_INVOKABLE void saveGlobalSetting (const QString& key, const QString& value);
Q_INVOKABLE QString loadGlobalSetting (const QString& key, const QString& defaultValue);
Q_INVOKABLE void saveBoolGlobalSetting (const QString& key, bool value);
......@@ -133,6 +136,9 @@ public:
void setIsVersionCheckEnabled (bool enable);
void setMavlinkSystemID (int id);
bool experimentalSurvey(void) const;
void setExperimentalSurvey(bool experimentalSurvey);
// Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox);
......@@ -146,6 +152,7 @@ signals:
void isVersionCheckEnabledChanged (bool enabled);
void mavlinkSystemIDChanged (int id);
void flightMapPositionChanged (QGeoCoordinate flightMapPosition);
void experimentalSurveyChanged (bool experimentalSurvey);
private:
FlightMapSettings* _flightMapSettings;
......
......@@ -30,6 +30,8 @@
#include "UAS.h"
#include "QGCApplication.h"
#include <QQmlEngine>
QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog")
const char* MultiVehicleManager::_gcsHeartbeatEnabledKey = "gcsHeartbeatEnabled";
......
......@@ -33,7 +33,6 @@
#include "FactGroup.h"
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "MissionItem.h"
#include "QmlObjectListModel.h"
#include "MAVLinkProtocol.h"
#include "UASMessageHandler.h"
......
......@@ -31,6 +31,9 @@
#include "QGCApplication.h"
#include "QGCFileDownload.h"
#include <QStandardPaths>
#include <QRegularExpression>
struct FirmwareToUrlElement_t {
FirmwareUpgradeController::AutoPilotStackType_t stackType;
FirmwareUpgradeController::FirmwareType_t firmwareType;
......
......@@ -34,6 +34,8 @@
#include <QDebug>
#include <QSettings>
#include <QUrl>
#include <QBitArray>
#include <QtCore/qmath.h>
#define kTimeOutMilliseconds 500
#define kGUIRateMilliseconds 17
......
......@@ -32,6 +32,9 @@ This file is part of the QGROUNDCONTROL project
#include <QApplication>
#include <QSslSocket>
#include <QProcessEnvironment>
#include <QHostAddress>
#include <QUdpSocket>
#include <QtPlugin>
#include "QGCApplication.h"
......
......@@ -242,6 +242,8 @@ Rectangle {
width: parent.width
}
//-----------------------------------------------------------------
//-- Offline mission editing settings
Row {
spacing: ScreenTools.defaultFontPixelWidth
......@@ -257,6 +259,19 @@ Rectangle {
indexModel: false
}
}
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: parent.width
}
//-----------------------------------------------------------------
//-- Experimental Survey settings
QGCCheckBox {
text: "Experimental Survey [WIP - no bugs reports please]"
checked: QGroundControl.experimentalSurvey
onClicked: QGroundControl.experimentalSurvey = checked
}
}
}
}
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