Unverified Commit d1580378 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5890 from DonLakeFlyer/MemoryReduction

Reduce memory footprint of Plan/Fly mission handling
parents dcb1c826 5f0128d3
......@@ -15,7 +15,8 @@ import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
// Adds visual items associated with the Flight Plan to the map
// Adds visual items associated with the Flight Plan to the map.
// Currently only used by Fly View even though it's called PlanMapItems!
Item {
id: _root
......@@ -45,24 +46,15 @@ Item {
}
}
// Waypoint lines
Instantiator {
model: largeMapView ? _missionController.waypointLines : 0
Item {
property var _missionLineViewComponent
Component.onCompleted: {
_missionLineViewComponent = missionLineViewComponent.createObject(map, {"object": object})
if (_missionLineViewComponent.status === Component.Error)
console.log(_missionLineViewComponent.errorString())
map.addMapItem(_missionLineViewComponent)
}
Component.onCompleted: {
_missionLineViewComponent = missionLineViewComponent.createObject(map)
if (_missionLineViewComponent.status === Component.Error)
console.log(_missionLineViewComponent.errorString())
map.addMapItem(_missionLineViewComponent)
}
Component.onDestruction: {
_missionLineViewComponent.destroy()
}
}
Component.onDestruction: {
_missionLineViewComponent.destroy()
}
Component {
......@@ -72,9 +64,7 @@ Item {
line.width: 3
line.color: "#be781c" // Hack, can't get palette to work in here
z: QGroundControl.zOrderWaypointLines
path: object ? [ object.coordinate1, object.coordinate2] : undefined
property var object
path: _missionController.waypointPath
}
}
}
......@@ -46,12 +46,15 @@ void CameraSectionTest::init(void)
QVERIFY(_spySection);
_validGimbalItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, MAV_CMD_DO_MOUNT_CONTROL, MAV_FRAME_MISSION, 10.1234, 0, 20.1234, 0, 0, 0, MAV_MOUNT_MODE_MAVLINK_TARGETING, true, false),
this);
_validTimeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false),
this);
_validDistanceItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
......@@ -62,6 +65,7 @@ void CameraSectionTest::init(void)
true, false),
this);
_validStartVideoItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, // sequence number
MAV_CMD_VIDEO_START_CAPTURE,
MAV_FRAME_MISSION,
......@@ -72,15 +76,19 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validStopVideoItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false),
this);
_validStopDistanceItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false),
this);
_validStopTimeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false),
this);
_validCameraPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
......@@ -91,6 +99,7 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validCameraVideoModeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
......@@ -101,6 +110,7 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validCameraSurveyPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
......@@ -111,6 +121,7 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validTakePhotoItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
MissionItem(0,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
......@@ -351,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, missionItem);
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
QVERIFY(item->cameraSection());
QCOMPARE(item->cameraSection()->available(), false);
}
......@@ -622,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Gimbal command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validGimbalItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validGimbalItem->missionItem());
invalidSimpleItem.missionItem().setParam2(10); // roll is not supported
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -712,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
*/
// Mode command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validCameraPhotoModeItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validCameraPhotoModeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -751,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
// Image start command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validTimeItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -792,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validDistanceItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validDistanceItem->missionItem());
invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -877,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validStartVideoItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStartVideoItem->missionItem());
invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0)
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -920,7 +931,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validStopVideoItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStopVideoItem->missionItem());
invalidSimpleItem.missionItem().setParam1(10); // must be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -993,7 +1004,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
// Take Photo command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validTimeItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......
......@@ -99,11 +99,8 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
fenceItems.append(item);
}
// Plan manager takes control of MissionItems, so no need to delete
_planManager.writeMissionItems(fenceItems);
for (int i=0; i<fenceItems.count(); i++) {
fenceItems[i]->deleteLater();
}
}
void GeoFenceManager::removeAll(void)
......
......@@ -175,7 +175,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
for (; i<newMissionItems.count(); i++) {
const MissionItem* missionItem = newMissionItems[i];
newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, *missionItem, this));
newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _editMode, *missionItem, this));
}
_deinitAllVisualItems();
......@@ -313,11 +313,8 @@ void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel*
_convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
// PlanManager takes control of MissionItems so no need to delete
vehicle->missionManager()->writeMissionItems(rgMissionItems);
for (int i=0; i<rgMissionItems.count(); i++) {
rgMissionItems[i]->deleteLater();
}
}
}
......@@ -1021,6 +1018,7 @@ void MissionController::_recalcWaypointLines(void)
CoordVectHashTable old_table = _linesTable;
_linesTable.clear();
_waypointLines.clear();
_waypointPath.clear();
bool linkEndToHome;
SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
......@@ -1042,22 +1040,33 @@ void MissionController::_recalcWaypointLines(void)
qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
linkStartToHome = true;
if (!_editMode) {
_waypointPath.append(QVariant::fromValue(lastCoordinateItem->coordinate()));
}
}
if (item->specifiesCoordinate()) {
if (!item->isStandaloneCoordinate()) {
firstCoordinateItem = false;
VisualItemPair pair(lastCoordinateItem, item);
if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
_addWaypointLineSegment(old_table, pair);
if (_editMode) {
VisualItemPair pair(lastCoordinateItem, item);
_addWaypointLineSegment(old_table, pair);
} else {
_waypointPath.append(QVariant::fromValue(item->coordinate()));
}
}
lastCoordinateItem = item;
}
}
}
if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
VisualItemPair pair(lastCoordinateItem, _settingsItem);
_addWaypointLineSegment(old_table, pair);
if (_editMode) {
VisualItemPair pair(lastCoordinateItem, _settingsItem);
_addWaypointLineSegment(old_table, pair);
} else {
_waypointPath.append(QVariant::fromValue(_settingsItem->coordinate()));
}
}
{
......@@ -1077,7 +1086,16 @@ void MissionController::_recalcWaypointLines(void)
_recalcMissionFlightStatus();
if (_waypointPath.count() == 0) {
// MapPolyLine has a bug where if you can from a path which has elements to an empty path the line drawn
// is not cleared from the map. This hack works around that since it causes the previous lines to be remove
// as then doesn't draw anything on the map.
_waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
_waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0)));
}
emit waypointLinesChanged();
emit waypointPathChanged();
}
void MissionController::_updateBatteryInfo(int waypointIndex)
......
......@@ -66,7 +66,8 @@ public:
} MissionFlightStatus_t;
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) ///< Used by Plan view only for interactive editing
Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) ///< Used by Fly view only for static display
Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged)
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
......@@ -146,6 +147,7 @@ public:
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
QVariantList waypointPath (void) { return _waypointPath; }
QStringList complexMissionItemNames (void) const;
QGeoCoordinate plannedHomePosition (void) const;
VisualMissionItem* currentPlanViewItem (void) const;
......@@ -167,27 +169,28 @@ public:
int batteriesRequired (void) const { return _missionFlightStatus.batteriesRequired; } ///< -1 for not supported
signals:
void visualItemsChanged(void);
void waypointLinesChanged(void);
void newItemsFromVehicle(void);
void missionDistanceChanged(double missionDistance);
void missionTimeChanged(void);
void missionHoverDistanceChanged(double missionHoverDistance);
void missionHoverTimeChanged(void);
void missionCruiseDistanceChanged(double missionCruiseDistance);
void missionCruiseTimeChanged(void);
void missionMaxTelemetryChanged(double missionMaxTelemetry);
void complexMissionItemNamesChanged(void);
void resumeMissionIndexChanged(void);
void resumeMissionReady(void);
void resumeMissionUploadFail(void);
void batteryChangePointChanged(int batteryChangePoint);
void batteriesRequiredChanged(int batteriesRequired);
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
void progressPctChanged(double progressPct);
void currentMissionIndexChanged(int currentMissionIndex);
void currentPlanViewIndexChanged();
void currentPlanViewItemChanged();
void visualItemsChanged (void);
void waypointLinesChanged (void);
void waypointPathChanged (void);
void newItemsFromVehicle (void);
void missionDistanceChanged (double missionDistance);
void missionTimeChanged (void);
void missionHoverDistanceChanged (double missionHoverDistance);
void missionHoverTimeChanged (void);
void missionCruiseDistanceChanged (double missionCruiseDistance);
void missionCruiseTimeChanged (void);
void missionMaxTelemetryChanged (double missionMaxTelemetry);
void complexMissionItemNamesChanged (void);
void resumeMissionIndexChanged (void);
void resumeMissionReady (void);
void resumeMissionUploadFail (void);
void batteryChangePointChanged (int batteryChangePoint);
void batteriesRequiredChanged (int batteriesRequired);
void plannedHomePositionChanged (QGeoCoordinate plannedHomePosition);
void progressPctChanged (double progressPct);
void currentMissionIndexChanged (int currentMissionIndex);
void currentPlanViewIndexChanged (void);
void currentPlanViewItemChanged (void);
private slots:
void _newMissionItemsAvailableFromVehicle(bool removeAllRequested);
......@@ -242,6 +245,7 @@ private:
QmlObjectListModel* _visualItems;
MissionSettingsItem* _settingsItem;
QmlObjectListModel _waypointLines;
QVariantList _waypointPath;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _itemsRequested;
......
......@@ -214,11 +214,6 @@ void MissionManager::generateResumeMission(int resumeIndex)
}
_resumeMission = true;
_writeMissionItemsWorker();
// Clean up no longer needed resume items
for (int i=0; i<resumeMission.count(); i++) {
resumeMission[i]->deleteLater();
}
}
/// Called when a new mavlink message for out vehicle is received
......
......@@ -85,8 +85,8 @@ void PlanManager::writeMissionItems(const QList<MissionItem*>& missionItems)
int firstIndex = skipFirstItem ? 1 : 0;
for (int i=firstIndex; i<missionItems.count(); i++) {
MissionItem* item = new MissionItem(*missionItems[i]);
_writeMissionItems.append(item);
MissionItem* item = missionItems[i];
_writeMissionItems.append(item); // PlanManager takes control of passed MissionItem
item->setIsCurrentItem(i == firstIndex);
......@@ -911,7 +911,8 @@ void PlanManager::removeAll(void)
void PlanManager::_clearAndDeleteMissionItems(void)
{
for (int i=0; i<_missionItems.count(); i++) {
_missionItems[i]->deleteLater();
// Using deleteLater here causes too much transient memory to stack up
delete _missionItems[i];
}
_missionItems.clear();
}
......@@ -920,7 +921,8 @@ void PlanManager::_clearAndDeleteMissionItems(void)
void PlanManager::_clearAndDeleteWriteMissionItems(void)
{
for (int i=0; i<_writeMissionItems.count(); i++) {
_writeMissionItems[i]->deleteLater();
// Using deleteLater here causes too much transient memory to stack up
delete _writeMissionItems[i];
}
_writeMissionItems.clear();
}
......
......@@ -47,6 +47,7 @@ public:
void loadFromVehicle(void);
/// Writes the specified set of mission items to the vehicle
/// IMPORTANT NOTE: PlanManager will take control of the MissionItem objects with the missionItems list. It will free them when done.
/// @param missionItems Items to send to vehicle
/// Signals sendComplete when done
void writeMissionItems(const QList<MissionItem*>& missionItems);
......
......@@ -37,7 +37,7 @@ void SectionTest::init(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, missionItem);
_simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
}
void SectionTest::cleanup(void)
......@@ -77,7 +77,7 @@ void SectionTest::_commonScanTest(Section* section)
QmlObjectListModel waypointVisualItems;
MissionItem waypointItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, waypointItem);
SimpleMissionItem simpleItem(_offlineVehicle, true /* editMode */, waypointItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
......
......@@ -85,7 +85,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
}
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missionItem, QObject* parent)
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent)
: VisualMissionItem(vehicle, parent)
, _missionItem(missionItem)
, _rawEdit(false)
......@@ -111,11 +111,16 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
_altitudeRelativeToHomeFact.setRawValue(true);
_isCurrentItem = missionItem.isCurrentItem();
_setupMetaData();
// In !editMode we skip some of the intialization to save memory
if (editMode) {
_setupMetaData();
}
_connectSignals();
_updateOptionalSections();
_syncFrameToAltitudeRelativeToHome();
_rebuildFacts();
if (editMode) {
_rebuildFacts();
}
}
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent)
......
......@@ -24,7 +24,7 @@ class SimpleMissionItem : public VisualMissionItem
public:
SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL);
SimpleMissionItem(Vehicle* vehicle, const MissionItem& missionItem, QObject* parent = NULL);
SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent = NULL);
SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL);
~SimpleMissionItem();
......
......@@ -100,7 +100,7 @@ void SimpleMissionItemTest::init(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, missionItem);
_simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
// It's important top check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
......@@ -139,7 +139,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem simpleMissionItem(vehicle, missionItem);
SimpleMissionItem simpleMissionItem(vehicle, true /* editMode */, missionItem);
// Validate that the fact values are correctly returned
......
......@@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, missionItem);
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
QVERIFY(item->speedSection());
QCOMPARE(item->speedSection()->available(), false);
}
......@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
double flightSpeed = 10.123456;
MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, validSpeedItem);
SimpleMissionItem simpleItem(_offlineVehicle, true /* editMode */, validSpeedItem);
MissionItem& simpleMissionItem = simpleItem.missionItem();
visualItems.append(&simpleItem);
scanIndex = 0;
......@@ -265,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Valid item in wrong position
QmlObjectListModel waypointVisualItems;
MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, waypointMissionItem);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, true /* editMode */, waypointMissionItem);
simpleMissionItem = validSpeedItem;
visualItems.append(&simpleWaypointItem);
visualItems.append(&simpleMissionItem);
......
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