Commit 319cf9c5 authored by DonLakeFlyer's avatar DonLakeFlyer

New MissionSettingsComplexItem

parent 019e06d4
......@@ -440,6 +440,7 @@ HEADERS += \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
src/MissionManager/MissionSettingsComplexItem.h \
src/MissionManager/PlanElementController.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/RallyPoint.h \
......@@ -610,6 +611,7 @@ SOURCES += \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/MissionSettingsComplexItem.cc \
src/MissionManager/PlanElementController.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/RallyPoint.cc \
......
......@@ -38,7 +38,6 @@
<file alias="MainWindowNative.qml">src/ui/MainWindowNative.qml</file>
<file alias="MavlinkSettings.qml">src/ui/preferences/MavlinkSettings.qml</file>
<file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/MissionEditor/MissionSettingsEditor.qml</file>
<file alias="MixersComponent.qml">src/AutoPilotPlugins/Common/MixersComponent.qml</file>
<file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file>
<file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file>
......@@ -67,6 +66,7 @@
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionItemMapVisual.qml">src/MissionEditor/MissionItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/MissionItemStatus.qml">src/MissionEditor/MissionItemStatus.qml</file>
<file alias="QGroundControl/Controls/MissionSettingsMapVisual.qml">src/MissionEditor/MissionSettingsMapVisual.qml</file>
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/MultiRotorMotorDisplay.qml">src/QmlControls/MultiRotorMotorDisplay.qml</file>
<file alias="QGroundControl/Controls/OfflineMapButton.qml">src/QmlControls/OfflineMapButton.qml</file>
......@@ -170,6 +170,7 @@
<file alias="SimpleItemEditor.qml">src/MissionEditor/SimpleItemEditor.qml</file>
<file alias="SurveyItemEditor.qml">src/MissionEditor/SurveyItemEditor.qml</file>
<file alias="FWLandingPatternEditor.qml">src/MissionEditor/FWLandingPatternEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/MissionEditor/MissionSettingsEditor.qml</file>
<file alias="TcpSettings.qml">src/ui/preferences/TcpSettings.qml</file>
<file alias="test.qml">src/test.qml</file>
<file alias="UdpSettings.qml">src/ui/preferences/UdpSettings.qml</file>
......@@ -183,11 +184,6 @@
<file alias="MavCmdInfoRover.json">src/MissionManager/MavCmdInfoRover.json</file>
<file alias="MavCmdInfoSub.json">src/MissionManager/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/MavCmdInfoVTOL.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
<file alias="App.SettingsGroup.json">src/Settings/App.SettingsGroup.json</file>
<file alias="AutoConnect.SettingsGroup.json">src/Settings/AutoConnect.SettingsGroup.json</file>
<file alias="Survey.SettingsGroup.json">src/MissionManager/Survey.SettingsGroup.json</file>
......@@ -196,6 +192,12 @@
<file alias="RallyPoint.FactMetaData.json">src/MissionManager/RallyPoint.FactMetaData.json</file>
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
<file alias="Vehicle/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file>
</qresource>
<qresource prefix="/MockLink">
......
......@@ -266,7 +266,8 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_MOUNT_CONFIGURE
<< MAV_CMD_DO_MOUNT_CONTROL;
<< MAV_CMD_DO_MOUNT_CONTROL
<< MAV_CMD_IMAGE_START_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE;
return list;
}
......
......@@ -210,9 +210,13 @@ FlightMap {
}
}
// Add the mission items to the map
MissionItemView {
// Add the mission item visuals to the map
Repeater {
model: _mainIsMap ? missionController.visualItems : 0
delegate: MissionItemMapVisual {
map: flightMap
}
}
// Add lines between waypoints
......
......@@ -25,7 +25,7 @@ MapItemView {
delegate: MissionItemIndicator {
id: itemIndicator
coordinate: object.coordinate
visible: object.specifiesCoordinate && (index != 0 || object.showHomePosition)
visible: object.specifiesCoordinate
z: QGroundControl.zOrderMapItems
missionItem: object
sequenceNumber: object.sequenceNumber
......
......@@ -49,9 +49,9 @@ Rectangle {
text: qsTr("WIP (NOT FOR REAL FLIGHT!)")
}
Item { width: 1; height: _margin }
SectionHeader { text: qsTr("Loiter point") }
SectionHeader {
text: qsTr("Loiter point")
}
Item { width: 1; height: _spacer }
......@@ -80,8 +80,6 @@ Rectangle {
onClicked: missionItem.loiterClockwise = checked
}
Item { width: 1; height: ScreenTools.defaultFontPixelHeight / 2 }
SectionHeader { text: qsTr("Landing point") }
Item { width: 1; height: _spacer }
......
......@@ -585,6 +585,7 @@ QGCView {
highlightMoveDuration: 250
delegate: MissionItemEditor {
map: editorMap
missionItem: object
width: parent.width
readOnly: false
......@@ -601,8 +602,7 @@ QGCView {
setCurrentItem(removeIndex)
}
onInsert: insertSimpleMissionItem(editorMap.center, index)
onMoveHomeToMapCenter: _visualItems.get(0).coordinate = editorMap.center
onInsert: insertSimpleMissionItem(editorMap.center, index)
}
} // QGCListView
} // Item - Mission Item editor
......
......@@ -18,13 +18,13 @@ Rectangle {
color: _currentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
radius: _radius
property var map ///< Map control
property var missionItem ///< MissionItem associated with this editor
property bool readOnly ///< true: read only view, false: full editing view
signal clicked
signal remove
signal insert
signal moveHomeToMapCenter
property bool _currentItem: missionItem.isCurrentItem
property color _outerTextColor: _currentItem ? "black" : qgcPal.text
......@@ -125,7 +125,7 @@ Rectangle {
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.left: label.right
anchors.top: parent.top
visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem
visible: missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem
text: missionItem.commandName
Component {
......@@ -141,9 +141,9 @@ Rectangle {
QGCLabel {
anchors.fill: commandPicker
visible: missionItem.sequenceNumber == 0 || !missionItem.isCurrentItem || !missionItem.isSimpleItem
visible: !missionItem.isCurrentItem || !missionItem.isSimpleItem
verticalAlignment: Text.AlignVCenter
text: missionItem.sequenceNumber == 0 ? qsTr("Mission Settings") : missionItem.commandName
text: missionItem.commandName
color: _outerTextColor
}
......@@ -154,7 +154,7 @@ Rectangle {
anchors.left: parent.left
anchors.top: commandPicker.bottom
height: item ? item.height : 0
source: missionItem.sequenceNumber == 0 ? "qrc:/qml/MissionSettingsEditor.qml" : missionItem.editorQml
source: missionItem.editorQml
onLoaded: {
item.visible = Qt.binding(function() { return _currentItem; })
......
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// Mission Settings map visuals
Item {
property var map ///< Map control to place item in
property var _missionItem: object
property var _itemVisual
property var _dragArea
property bool _itemVisualShowing: false
property bool _dragAreaShowing: false
function hideItemVisuals() {
if (_itemVisualShowing) {
_itemVisual.destroy()
_itemVisualShowing = false
}
}
function showItemVisuals() {
if (!_itemVisualShowing) {
_itemVisual = indicatorComponent.createObject(map)
map.addMapItem(_itemVisual)
_itemVisualShowing = true
}
}
function hideDragArea() {
if (_dragAreaShowing) {
_dragArea.destroy()
_dragAreaShowing = false
}
}
function showDragArea() {
if (!_dragAreaShowing && _missionItem.specifiesCoordinate) {
_dragArea = dragAreaComponent.createObject(map)
_dragAreaShowing = true
}
}
Component.onCompleted: {
showItemVisuals()
if (_missionItem.isCurrentItem) {
showDragArea()
}
}
Component.onDestruction: {
hideDragArea()
hideItemVisuals()
}
Connections {
target: _missionItem
onIsCurrentItemChanged: {
if (_missionItem.isCurrentItem) {
showDragArea()
} else {
hideDragArea()
}
}
}
// Control which is used to drag items
Component {
id: dragAreaComponent
MissionItemIndicatorDrag {
itemIndicator: _itemVisual
itemCoordinate: _missionItem.coordinate
onItemCoordinateChanged: _missionItem.coordinate = itemCoordinate
}
}
Component {
id: indicatorComponent
MissionItemIndicator {
coordinate: _missionItem.coordinate
visible: _missionItem.showHomePosition
z: QGroundControl.zOrderMapItems
missionItem: _missionItem
onClicked: setCurrentItem(_missionItem.sequenceNumber)
// These are the non-coordinate child mission items attached to this item
Row {
anchors.top: parent.top
anchors.left: parent.right
Repeater {
model: _missionItem.childItems
delegate: MissionItemIndexLabel {
label: object.abbreviation
checked: object.isCurrentItem
z: 2
specifiesCoordinate: false
onClicked: setCurrentItem(object.sequenceNumber)
}
}
}
}
}
}
......@@ -5,20 +5,55 @@ import QtQuick.Layouts 1.2
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
Column {
QGCMouseArea {
id: _root
anchors.left: parent.left
anchors.right: parent.right
height: column.height
onClicked: checked = !checked
property alias text: label.text
property alias text: label.text
property bool checked: true
property bool showSpacer: true
property ExclusiveGroup exclusiveGroup: null
QGCPalette { id: qgcPal; colorGroupEnabled: true }
property real _sectionSpacer: ScreenTools.defaultFontPixelWidth / 2 // spacing between section headings
onExclusiveGroupChanged: {
if (exclusiveGroup)
exclusiveGroup.bindCheckable(_root)
}
QGCLabel { id: label }
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Rectangle {
ColumnLayout {
id: column
anchors.left: parent.left
anchors.right: parent.right
height: 1
color: qgcPal.text
Item {
height: _sectionSpacer
width: 1
visible: showSpacer
}
QGCLabel {
id: label
Layout.fillWidth: true
Image {
anchors.right: parent.right
anchors.verticalCenter: parent.verticalCenter
source: "/qmlimages/arrow-down.png"
visible: !_root.checked
}
}
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: 1
color: qgcPal.text
}
}
}
......@@ -166,7 +166,10 @@ Rectangle {
anchors.right: parent.right
spacing: _margin
SectionHeader { text: qsTr("Camera") }
SectionHeader {
text: qsTr("Camera")
showSpacer: false
}
QGCComboBox {
id: gridTypeCombo
......@@ -327,8 +330,6 @@ Rectangle {
}
}
Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
SectionHeader { text: qsTr("Grid") }
GridLayout {
......@@ -395,8 +396,6 @@ Rectangle {
spacing: _margin
visible: gridTypeCombo.currentIndex == _gridTypeManual
Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
SectionHeader { text: qsTr("Grid") }
FactTextFieldGrid {
......@@ -447,8 +446,6 @@ Rectangle {
}
}
Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
SectionHeader { text: qsTr("Statistics") }
Grid {
......
......@@ -105,8 +105,10 @@ void FixedWingLandingComplexItem::setDirty(bool dirty)
}
}
void FixedWingLandingComplexItem::save(QJsonObject& saveObject) const
void FixedWingLandingComplexItem::save(QJsonArray& missionItems) const
{
QJsonObject saveObject;
saveObject[JsonHelper::jsonVersionKey] = 1;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
......@@ -128,6 +130,8 @@ void FixedWingLandingComplexItem::save(QJsonObject& saveObject) const
saveObject[_jsonLoiterClockwiseKey] = _loiterClockwise;
saveObject[_jsonLoiterAltitudeRelativeKey] = _loiterAltitudeRelative;
saveObject[_jsonLandingAltitudeRelativeKey] = _landingAltitudeRelative;
missionItems.append(saveObject);
}
void FixedWingLandingComplexItem::setSequenceNumber(int sequenceNumber)
......@@ -236,7 +240,7 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const
0.0, 0.0, 0.0, 0.0, // param 1-4
_landingCoordinate.latitude(),
_landingCoordinate.longitude(),
0.0, // altitude
_landingAltitudeFact.rawValue().toDouble(),
true, // autoContinue
false, // isCurrentItem
pMissionItems); // parent - allow delete on pMissionItems to delete everthing
......
......@@ -80,7 +80,7 @@ public:
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final { setLoiterCoordinate(coordinate); }
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonObject& saveObject) const final;
void save (QJsonArray& missionItems) const final;
static const char* jsonComplexItemTypeValue;
......
......@@ -965,11 +965,58 @@
{ "id": 510, "rawName": "MAV_CMD_GET_MESSAGE_INTERVAL", "friendlyName": "Get message interval" },
{ "id": 511, "rawName": "MAV_CMD_SET_MESSAGE_INTERVAL", "friendlyName": "Set message interval" },
{ "id": 520, "rawName": "MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES", "friendlyName": "Get capabilities" },
{ "id": 2000, "rawName": "MAV_CMD_IMAGE_START_CAPTURE", "friendlyName": "Start image capture" },
{
"id": 2000,
"rawName": "MAV_CMD_IMAGE_START_CAPTURE",
"friendlyName": "Start image capture" ,
"description": "Start taking one or more photos.",
"category": "Camera",
"param1": {
"label": "Interval",
"default": 0,
"units": "secs",
"decimalPlaces": 0
},
"param2": {
"label": "Photo count",
"default": 1,
"decimalPlaces": 0
},
"param3": {
"label": "Resolution",
"default": -1,
"decimalPlaces": 0
},
"param6": {
"label": "Camera id",
"default": 0,
"decimalPlaces": 0
}
},
{ "id": 2001, "rawName": "MAV_CMD_IMAGE_STOP_CAPTURE", "friendlyName": "Stop image capture" },
{ "id": 2003, "rawName": "MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName": "Trigger control" },
{ "id": 2500, "rawName": "MAV_CMD_VIDEO_START_CAPTURE", "friendlyName": "Start video capture" },
{ "id": 2501, "rawName": "MAV_CMD_VIDEO_STOP_CAPTURE", "friendlyName": "Stop video cpture" },
{
"id": 2500,
"rawName": "MAV_CMD_VIDEO_START_CAPTURE",
"friendlyName": "Start video capture",
"description": "Start taking video.",
"category": "Camera",
"param1": {
"label": "Camera id",
"default": 0,
"decimalPlaces": 0
},
"param2": {
"label": "FPS",
"default": -1,
"decimalPlaces": 0
},
"param3": {
"label": "Resolution",
"default": -1,
"decimalPlaces": 0
}
},
{ "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" },
{
"id": 3000,
......
This diff is collapsed.
......@@ -34,11 +34,10 @@ public:
MissionController(QObject* parent = NULL);
~MissionController();
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
// Mission settings
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(QStringList complexMissionItemNames MEMBER _complexMissionItemNames CONSTANT)
Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged)
......@@ -67,9 +66,8 @@ public:
/// @param[in] vehicle Vehicle we are loading items for
/// @param[in] filename File to load from
/// @param[out] visualItems Visual items loaded, returns NULL if error
/// @param[out] complexItems Complex items loaded, returns NULL if error
/// @return success/fail
static bool loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems);
static bool loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems);
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
......@@ -94,7 +92,6 @@ public:
QGeoCoordinate plannedHomePosition (void);
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* complexVisualItems (void) { return _complexItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
double missionDistance (void) const { return _missionDistance; }
......@@ -110,7 +107,6 @@ public:
signals:
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
void visualItemsChanged(void);
void complexVisualItemsChanged(void);
void waypointLinesChanged(void);
void newItemsFromVehicle(void);
void missionDistanceChanged(double missionDistance);
......@@ -151,10 +147,10 @@ private:
bool _findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame);
static double _normalizeLat(double lat);
static double _normalizeLon(double lon);
static void _addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter);
static bool _loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
static bool _loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
static bool _loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
static void _addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter);
static bool _loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString);
static bool _loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
static bool _loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
static bool _loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
int _nextSequenceNumber(void);
void _setMissionDistance(double missionDistance);
......@@ -171,7 +167,6 @@ private:
private:
QmlObjectListModel* _visualItems;
QmlObjectListModel* _complexItems;
QmlObjectListModel _waypointLines;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
......@@ -189,6 +184,8 @@ private:
QStringList _complexMissionItemNames;
static const char* _settingsGroup;
// Json file keys for persistence
static const char* _jsonFileTypeValue;
static const char* _jsonFirmwareTypeKey;
static const char* _jsonVehicleTypeKey;
......
......@@ -91,7 +91,7 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
/// This begins the write sequence with the vehicle. This may be called during a retry.
void MissionManager::_writeMissionCount(void)
{
qCDebug(MissionManagerLog) << "_writeMissionCount retry count" << _retryCount;
qCDebug(MissionManagerLog) << "_writeMissionCount count:_retryCount" << _missionItems.count() << _retryCount;
mavlink_message_t message;
mavlink_mission_count_t missionCount;
......@@ -427,7 +427,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool m
seq = missionItem.seq;
}
qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << seq;
qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << seq << command;
if (_itemIndicesToRead.contains(seq)) {
_itemIndicesToRead.removeOne(seq);
......@@ -483,8 +483,6 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
mavlink_msg_mission_request_decode(&message, &missionRequest);
qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq;
if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
if (missionRequest.seq > _missionItems.count()) {
_sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_missionItems.count()).arg(missionRequest.seq));
......@@ -497,11 +495,13 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
_itemIndicesToWrite.removeOne(missionRequest.seq);
}
mavlink_message_t messageOut;
MissionItem* item = _missionItems[missionRequest.seq];
qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq << item->command();
mavlink_message_t messageOut;
if (missionItemInt) {
mavlink_mission_item_int_t missionItem;
MissionItem* item = _missionItems[missionRequest.seq];
missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
......@@ -526,8 +526,6 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
} else {
mavlink_mission_item_t missionItem;
MissionItem* item = _missionItems[missionRequest.seq];
missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionItem.seq = missionRequest.seq;
......
[
{
"name": "PlannedHomePositionLatitude",
"shortDescription": "Planned home position latitude",
"type": "double",
"decimalPlaces": 7,
"defaultValue": 37.803784
},
{
"name": "PlannedHomePositionLongitude",
"shortDescription": "Planned home position longitude",
"type": "double",
"decimalPlaces": 7,
"defaultValue": -122.462276
},
{
"name": "PlannedHomePositionAltitude",
"shortDescription": "Planned home position altitude",
"type": "double",
"units": "m",
"decimalPlaces": 1,
"defaultValue": 0
},
{
"name": "FlightSpeed",
"shortDescription": "Flight speed for mission.",
"type": "double",
"units": "m/s",
"min": 0,
"decimalPlaces": 1
},
{
"name": "CameraAction",
"shortDescription": "Specify whether the camera should take photos or video",
"type": "uint32",
"enumStrings": "No camera action,Take photos (time),Take photos (distance),Take video",
"enumValues": "0,1,2,3",
"defaultValue": 0
},
{
"name": "CameraPhotoIntervalDistance",
"shortDescription": "Specify the distance between each photo",
"type": "double",
"units": "m",
"min": 0,
"decimalPlaces": 1,
"defaultValue": 1
},
{
"name": "CameraPhotoIntervalTime",
"shortDescription": "Specify the time between each photo",
"type": "uint32",
"units": "secs",
"min": 1,
"decimalPlaces": 0,
"defaultValue": 10
},
{
"name": "GimbalPitch",
"shortDescription": "Gimbal pitch rotation.",