Commit eb694b02 authored by Valentin Platzgummer's avatar Valentin Platzgummer
parents 72ba8f6f 86426f23
......@@ -26,6 +26,8 @@ WiMA is a abbreviation for \textbf{Wi}reless \textbf{M}easurement \textbf{A}ppli
This document was created to explain the functionality of the WiMA-Extension at one hand, and to encourage the reader to find bugs inside the program. As the extension is still being developed the contents demonstrated inside this document may differ from those ones in the program.
The folder "deploy" in the QGroundControl root directory (can be cloned from Gitlab) contains a AppImage of the program. QGroundControl can be launched by double-clicking the AppImage. Currently only a Linux version is available.
A Documentation of the QGroundControl program can be found under \url{https://docs.qgroundcontrol.com/en/}.
\section{Documentation}
......
......@@ -227,7 +227,9 @@
<file alias="QGroundControl/Controls/CoordinateIndicator.qml">src/WimaView/CoordinateIndicator.qml</file>
<file alias="QGroundControl/Controls/WimaJoinedAreaMapVisual.qml">src/WimaView/WimaJoinedAreaMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaCorridorEditor.qml">src/WimaView/WimaCorridorEditor.qml</file>
<file>src/FlightMap/MapItems/WimaPlanMapItems.qml</file>
<file alias="QGroundControl/FlightMap/WimaPlanMapItems.qml">src/FlightMap/MapItems/WimaPlanMapItems.qml</file>
<file alias="QGroundControl/FlightMap/WimaMissionItemMapVisual.qml">src/PlanView/WimaMissionItemMapVisual.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayWimaMenu.qml">src/FlightDisplay/FlightDisplayWimaMenu.qml</file>
</qresource>
<qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
......
......@@ -510,17 +510,25 @@ QGCView {
}
}
FlightDisplayViewWidgets {
id: flightDisplayViewWidgets
// FlightDisplayViewWidgets {
// id: flightDisplayViewWidgets
// z: _panel.z + 4
// height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
// anchors.left: parent.left
// anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
// anchors.bottom: parent.bottom
// qgcView: root
// useLightColors: isBackgroundDark
// missionController: _missionController
// visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
// }
FlightDisplayWimaMenu {
id: wimaMenu
z: _panel.z + 4
height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.bottom: parent.bottom
qgcView: root
useLightColors: isBackgroundDark
missionController: _missionController
visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
}
//-------------------------------------------------------------------------
......
......@@ -205,18 +205,16 @@ FlightMap {
: object.type === "WimaMeasurementAreaData" ? "green"
: "transparent"
opacity: 0.25
z: QGroundControl.zOrderTrajectoryLines-1
z: QGroundControl.zOrderTrajectoryLines-2
}
}
// Add mission items generated by wima planer to the map
PlanMapItems {
WimaPlanMapItems {
map: flightMap
largeMapView: _mainIsMap
masterController: masterController
isActiveVehicle: _vehicle.active
property var _vehicle: object
wimaController: flightMap.wimaController
z: QGroundControl.zOrderTrajectoryLines-1
}
// Add trajectory points to the map
......
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Airmap 1.0
Item {
id: _root
Rectangle {
anchors.top: parent.top
color: "white"
height: 100
width: 200
QGCCheckBox {
id: enableWima
text: qsTr("WiMA")
}
}
}
......@@ -15,4 +15,5 @@ PreFlightGPSCheck 1.0 PreFlightGPSCheck.qml
PreFlightRCCheck 1.0 PreFlightRCCheck.qml
PreFlightSensorsHealthCheck 1.0 PreFlightSensorsHealthCheck.qml
PreFlightSoundCheck 1.0 PreFlightSoundCheck.qml
FlightDisplayWimaMenu 1.0 FlightDisplayWimaMenu.qml
[Dolphin]
PreviewsShown=true
Timestamp=2019,10,13,16,25,8
Version=4
......@@ -21,6 +21,7 @@ MapQuickItem {
property var missionItem
property int sequenceNumber
property var color
signal clicked
......@@ -37,6 +38,8 @@ MapQuickItem {
vehicleYaw: missionItem.missionVehicleYaw
showGimbalYaw: !isNaN(missionItem.missionGimbalYaw)
onClicked: _item.clicked()
color: _item.color ? _item.color
: checked ? "green" : (child ? qgcPal.mapIndicatorChild : qgcPal.mapIndicator)
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
}
......
......@@ -16,41 +16,71 @@ import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
// Adds visual items generated by wima planer to the map.
// Currently only used by Fly View even though it's called PlanMapItems!
Item {
id: _root
property var map ///< Map control to show items on
property bool largeMapView ///< true: map takes up entire view, false: map is in small window
property var wimaController value
property var map ///< Map control to show items on
property bool largeMapView ///< true: map takes up entire view, false: map is in small window
property var wimaController
property string mIColor: "#B4808080" // Mission Items Color, gray with alpha 0.7 #AARRGGBB
property string mIlineColor: mIColor
property string cMIColor: "orangered" // Current Mission Items Color
property string cMIlineColor: cMIColor
property var _map: map
property var _map: map
property var _missionLineViewComponent
property var _currentMissionLineViewComponent
// Add the mission item visuals to the map
Repeater {
model: largeMapView ? _missionController.visualItems : 0
model: largeMapView ? wimaController.missionItems : 0
delegate: MissionItemMapVisual {
delegate: WimaMissionItemMapVisual {
map: _map
onClicked: {
if (isActiveVehicle) {
// Only active vehicle supports click to change current mission item
guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, Math.max(object.sequenceNumber, 1))
}
}
color: _root.mIColor
// onClicked: {
// if (isActiveVehicle) {
// // Only active vehicle supports click to change current mission item
// guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, Math.max(object.sequenceNumber, 1))
// }
// }
}
/*onItemAdded: {
console.log(wimaController.missionItems.count)
}
onItemRemoved: {
console.log(wimaController.missionItems.count)
}*/
}
// Add the current mission item visuals to the map
Repeater {
model: largeMapView ? wimaController.currentMissionItems : 0
delegate: WimaMissionItemMapVisual {
map: _map
color: _root.cMIColor
}
}
Component.onCompleted: {
_missionLineViewComponent = missionLineViewComponent.createObject(map)
if (_missionLineViewComponent.status === Component.Error)
console.log(_missionLineViewComponent.errorString())
map.addMapItem(_missionLineViewComponent)
_currentMissionLineViewComponent = currentMissionLineViewComponent.createObject(map)
if (_currentMissionLineViewComponent.status === Component.Error)
console.log(_currentMissionLineViewComponent.errorString())
map.addMapItem(_currentMissionLineViewComponent)
}
Component.onDestruction: {
_missionLineViewComponent.destroy()
_currentMissionLineViewComponent.destroy()
}
Component {
......@@ -58,9 +88,20 @@ Item {
MapPolyline {
line.width: 3
line.color: "#be781c" // Hack, can't get palette to work in here
line.color: mIlineColor
z: QGroundControl.zOrderWaypointLines
path: wimaController.waypointPath
}
}
Component {
id: currentMissionLineViewComponent
MapPolyline {
line.width: 3
line.color: cMIlineColor
z: QGroundControl.zOrderWaypointLines
path: _missionController.waypointPath
path: wimaController.currentWaypointPath
}
}
}
......@@ -25,5 +25,6 @@ MissionItemIndicatorDrag 1.0 MissionItemIndicatorDrag.qml
MissionItemView 1.0 MissionItemView.qml
MissionLineView 1.0 MissionLineView.qml
PlanMapItems 1.0 PlanMapItems.qml
WimaPlanMapItems 1.0 WimaPlanMapItems.qml
PolygonEditor 1.0 PolygonEditor.qml
VehicleMapItem 1.0 VehicleMapItem.qml
......@@ -386,6 +386,34 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
return newItem->sequenceNumber();
}
int MissionController::insertSimpleMissionItem(const MissionItem &missionItem, int i)
{
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initVisualItem(newItem);
MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
if (newItem->command() == takeoffCmd) {
if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
return -1; // can not add this takeoff command for this vehicle
}
}
if (newItem->specifiesAltitude()) {
double prevAltitude;
int prevAltitudeMode;
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
}
}
newItem->setMissionFlightStatus(_missionFlightStatus);
_visualItems->insert(i, newItem);
return newItem->sequenceNumber();
}
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
int sequenceNumber = _nextSequenceNumber();
......
......@@ -108,6 +108,11 @@ public:
/// @return Sequence number for new item
Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int i);
/// Add a new simple mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
int insertSimpleMissionItem(const MissionItem &missionItem, int i);
/// Add a new ROI mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
......
......@@ -148,7 +148,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
: VisualMissionItem (other, flyView, parent)
, _missionItem (other._vehicle)
, _missionItem (other._missionItem, this)
, _rawEdit (false)
, _dirty (false)
, _ignoreDirtyChangeSignals (false)
......
......@@ -79,7 +79,7 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o
_vehicle = other._vehicle;
setIsCurrentItem(other._isCurrentItem);
setDirty(other._dirty);
_dirty = other._dirty;
_homePositionSpecialCase = other._homePositionSpecialCase;
_terrainAltitude = other._terrainAltitude;
setAltDifference(other._altDifference);
......
/****************************************************************************
*
* (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
/// Simple Mission Item visuals
Item {
id: _root
property var map ///< Map control to place item in
property var qgcView ///< QGCView to use for popping dialogs
property var color
property var _missionItem: object
property var _itemVisual
property var _dragArea
property bool _itemVisualShowing: false
property bool _dragAreaShowing: false
signal clicked(int sequenceNumber)
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 && map.planView) {
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 {
mapControl: _root.map
itemIndicator: _itemVisual
itemCoordinate: _missionItem.coordinate
onItemCoordinateChanged: _missionItem.coordinate = itemCoordinate
}
}
Component {
id: indicatorComponent
MissionItemIndicator {
coordinate: _missionItem.coordinate
visible: _missionItem.specifiesCoordinate
z: QGroundControl.zOrderMapItems
missionItem: _missionItem
sequenceNumber: _missionItem.sequenceNumber
color: _root.color
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
add refpt gui and edit constructor
new path optim required for circ survey
add gui elements for circ survey
solve bug for cantFindPath.wima on Desktop/WimaPath
......@@ -26,6 +26,16 @@ QVariantList WimaAreaData::path() const
return _path;
}
QList<QGeoCoordinate> WimaAreaData::coordinateList() const
{
QList<QGeoCoordinate> coordinateList;
for ( auto coorinate : _path)
coordinateList.append(coorinate.value<QGeoCoordinate>());
return coordinateList;
}
/*!
* \fn void WimaAreaData::setMaxAltitude(double maxAltitude)
*
......
......@@ -19,8 +19,9 @@ public:
//WimaAreaData(const WimaArea &other, QObject *parent = nullptr);
WimaAreaData& operator=(const WimaAreaData& otherData) = delete; // avoid slicing
double maxAltitude() const;
QVariantList path() const;
double maxAltitude() const;
QVariantList path() const;
QList<QGeoCoordinate> coordinateList() const;
virtual QString type() const = 0;
......
This diff is collapsed.
......@@ -39,21 +39,27 @@ public:
Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT)
Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT)
Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged)
Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* currentMissionItems READ currentMissionItems NOTIFY currentMissionItemsChanged)
Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged)
Q_PROPERTY(QVariantList currentWaypointPath READ currentWaypointPath NOTIFY currentWaypointPathChanged)
// Property accessors
PlanMasterController* masterController (void) { return _masterController; }
MissionController* missionController (void) { return _missionController; }
QmlObjectListModel* visualItems (void) ;
QmlObjectListModel* visualItems (void);
QString currentFile (void) const { return _currentFile; }
QStringList loadNameFilters (void) const;
QStringList saveNameFilters (void) const;
QString fileExtension (void) const { return wimaFileExtension; }
QGCMapPolygon joinedArea (void) const;
WimaDataContainer* dataContainer (void) const;
WimaDataContainer* dataContainer (void);
QmlObjectListModel* missionItems (void);
QmlObjectListModel* currentMissionItems (void);
QVariantList waypointPath (void);
QVariantList currentWaypointPath (void);
// Property setters
......@@ -62,11 +68,11 @@ public:
void setDataContainer (WimaDataContainer* container);
// Member Methodes
Q_INVOKABLE void nextPhase();
Q_INVOKABLE void startMission();
Q_INVOKABLE void abortMission();
Q_INVOKABLE void pauseMission();
Q_INVOKABLE void resumeMission();
Q_INVOKABLE bool updateMission();
Q_INVOKABLE void saveToCurrent ();
Q_INVOKABLE void saveToFile (const QString& filename);
......@@ -82,6 +88,16 @@ public:
// Member Methodes
QJsonDocument saveToJson(FileType fileType);
bool calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path);
/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList
bool extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList);
/// extracts the coordinates (between startIndex and endIndex) stored in missionItems (list of MissionItems) and stores them in coordinateList.
bool extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex);
/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList
bool extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList);
/// extracts the coordinates (between startIndex and endIndex) stored in missionItems (list of MissionItems) and stores them in coordinateList.
bool extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex);
signals:
void masterControllerChanged (void);
void missionControllerChanged (void);
......@@ -90,9 +106,16 @@ signals:
void dataContainerChanged ();
void readyForSaveSendChanged (bool ready);
void missionItemsChanged (void);
void currentMissionItemsChanged (void);
void waypointPathChanged (void);
void currentWaypointPathChanged (void);
private slots:
void containerDataValidChanged (bool valid);
void updateCurrentMissionItems (void);
void updateWaypointPath (void);
void updateCurrentPath (void);
private:
PlanMasterController *_masterController;
......@@ -105,6 +128,12 @@ private:
WimaServiceAreaData _serviceArea; // area for supplying
WimaCorridorData _corridor; // corridor connecting opArea and serArea
bool _localPlanDataValid;
QmlObjectListModel _missionItems;
QmlObjectListModel _missionItems; // all mission itmes (Mission Items) generaded by wimaPlaner, displayed in flightView
QmlObjectListModel _currentMissionItems; // contains the current mission items, which are a sub set of _missionItems,
// _currentMissionItems contains a number of mission items which can be worked off with a single battery chrage
QVariantList _waypointPath; // path connecting the items in _missionItems
QVariantList _currentWaypointPath; // path connecting the items in _currentMissionItems
int _startWaypointIndex; // index to the mission item stored in _missionItems defining the first element of _currentMissionItems
int _endWaypointIndex; // index to the mission item stored in _missionItems defining the last element of _currentMissionItems
};
......@@ -20,10 +20,12 @@ WimaPlanData::WimaPlanData(const WimaPlanData &other, QObject *parent)
*/
WimaPlanData &WimaPlanData::operator=(const WimaPlanData &other)
{
// copy wima areas
QList<const WimaAreaData*> areaList = other.areaList();
_areaList.clear();
for (int i = 0; i < areaList.size(); i++) {
const WimaAreaData *areaData = areaList[i];
// determine area type and append
if (areaData->type() == WimaJoinedAreaData::typeString) {
this->append(*qobject_cast<const WimaJoinedAreaData*>(areaData));
}else if (areaData->type() == WimaServiceAreaData::typeString) {
......@@ -35,6 +37,9 @@ WimaPlanData &WimaPlanData::operator=(const WimaPlanData &other)
}
}
// copy mission items
_missionItems = other.missionItems();
return *this;
}
......
......@@ -242,7 +242,6 @@ bool WimaPlaner::updateMission()
qWarning("WimaPlaner::updateMission(): settingsItem == nullptr");
return false;
}
// set altitudes, temporary measure to solve bugs
QGeoCoordinate center = _serviceArea.center();
center.setAltitude(0);
......@@ -253,15 +252,20 @@ bool WimaPlaner::updateMission()
center = _corridor.center();
center.setAltitude(0);
_corridor.setCenter(center);
// set HomePos. to serArea center
settingsItem->setCoordinate(_serviceArea.center());
// create take off position item
int sequenceNumber = _missionController->insertSimpleMissionItem(_serviceArea.center(), missionItems->count());
_missionController->setCurrentPlanViewIndex(sequenceNumber, true);
_missionController->setCurrentPlanViewIndex(sequenceNumber, true);
SimpleMissionItem* takeOffItem = qobject_cast<SimpleMissionItem*>(missionItems->get(missionItems->count()-1));
if (takeOffItem == nullptr){
qWarning("WimaPlaner::updateMission(): takeOffItem == nullptr");
return false;
} else {
takeOffItem->setCoordinate(_serviceArea.center()); //necessary, insertSimpleMissionItem does not copy coordinate (why?)
}
// create survey item, will be extened with more()-> mission types in the future
_missionController->insertComplexMissionItem(_missionController->circularSurveyComplexItemName(), _measurementArea.center(), missionItems->count());
......@@ -280,13 +284,9 @@ bool WimaPlaner::updateMission()
survey->setAutoGenerated(true); // prevents reinitialisation from gui
survey->surveyAreaPolygon()->clear();
survey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList());
}
// calculate path from take off to opArea
if (survey->visualTransectPoints().size() == 0) {
qWarning("WimaPlaner::updateMission(): survey no points.");
......@@ -345,6 +345,8 @@ bool WimaPlaner::updateMission()
MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
landItem->setCommand(landCmd);
} else {
return false;
}
}
......@@ -588,26 +590,6 @@ bool WimaPlaner::recalcJoinedArea(QString &errorString)
return false; // this happens if all areas are pairwise disjoint
}
// join service area, op area and corridor
// // remove if debugging finished
// WimaServiceArea *test = new WimaServiceArea(this);
// WimaServiceArea *test1 = new WimaServiceArea(this);
// WimaServiceArea *test2 = new WimaServiceArea(this);
// WimaServiceArea *test3 = new WimaServiceArea(this);
// Circle circle(25, this);
// using namespace GeoUtilities;
// test->setPath(toGeo(circle.approximateSektor(0.5, 1, 3), _joinedArea.center()));
// _visualItems.append(test);
// test1->setPath(toGeo(circle.approximateSektor(0.5, 1, -1), _joinedArea.center()));
// _visualItems.append(test1);
// test2->setPath(toGeo(circle.approximateSektor(0.5,-1, 3), _joinedArea.center()));
// _visualItems.append(test2);
// test3->setPath(toGeo(circle.approximateSektor(0.5, -1, -3), _joinedArea.center()));
// _visualItems.append(test3);
return true;
}
......@@ -682,6 +664,21 @@ WimaPlanData WimaPlaner::toPlanData()
// convert mission items to mavlink commands
QList<MissionItem*> rgMissionItems;
MissionController::convertToMissionItems(_missionController->visualItems(), rgMissionItems, this);
// remove warnings if you read this
// qWarning("WimaPlaner::toPlanData(): rgMissionItems");
// for (auto item : rgMissionItems) {
// qWarning() << item->command();
// qWarning() << item->param1();
// qWarning() << item->param2();
// qWarning() << item->param3();
// qWarning() << item->param4();
// qWarning() << item->param5();
// qWarning() << item->param6();
// qWarning() << item->param7();
// qWarning(" ");
// }
QList<const MissionItem*> rgMissionItemsConst;
for (auto missionItem : rgMissionItems)
rgMissionItemsConst.append(missionItem);
......
......@@ -109,6 +109,8 @@ public:
QJsonDocument saveToJson(FileType fileType);
bool calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path);
// static Members
static const char* wimaFileExtension;
static const char* areaItemsName;
......@@ -127,7 +129,6 @@ private slots:
void recalcPolygonInteractivity (int index);
bool recalcJoinedArea (QString &errorString);
void pushToContainer ();
bool calcShortestPath (const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path);
private:
// Member Functions
......
......@@ -6,3 +6,6 @@ How to exchange mission between WimaPlaner and WimaController.
4) start/continue mission
5) return vehicle on battery low
6) go to 4) or quit if last waypoint reached
investigate load, loadFromVehicle, syncInProgress, _newMissionItemsAvailableFromVehicle
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