Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
5f0128d3
Commit
5f0128d3
authored
Dec 15, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Reduce memory footprint of Plan/Fly mission handling
parent
dcb1c826
Changes
13
Hide whitespace changes
Inline
Side-by-side
Showing
13 changed files
with
107 additions
and
84 deletions
+107
-84
PlanMapItems.qml
src/FlightMap/MapItems/PlanMapItems.qml
+11
-21
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+19
-8
GeoFenceManager.cc
src/MissionManager/GeoFenceManager.cc
+1
-4
MissionController.cc
src/MissionManager/MissionController.cc
+27
-9
MissionController.h
src/MissionManager/MissionController.h
+26
-22
MissionManager.cc
src/MissionManager/MissionManager.cc
+0
-5
PlanManager.cc
src/MissionManager/PlanManager.cc
+6
-4
PlanManager.h
src/MissionManager/PlanManager.h
+1
-0
SectionTest.cc
src/MissionManager/SectionTest.cc
+2
-2
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+8
-3
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+1
-1
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+2
-2
SpeedSectionTest.cc
src/MissionManager/SpeedSectionTest.cc
+3
-3
No files found.
src/FlightMap/MapItems/PlanMapItems.qml
View file @
5f0128d3
...
@@ -15,7 +15,8 @@ import QGroundControl 1.0
...
@@ -15,7 +15,8 @@ import QGroundControl 1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FlightMap
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
{
Item
{
id
:
_root
id
:
_root
...
@@ -45,24 +46,15 @@ Item {
...
@@ -45,24 +46,15 @@ Item {
}
}
}
}
// Waypoint lines
Component
.
onCompleted
:
{
Instantiator
{
_missionLineViewComponent
=
missionLineViewComponent
.
createObject
(
map
)
model
:
largeMapView
?
_missionController
.
waypointLines
:
0
if
(
_missionLineViewComponent
.
status
===
Component
.
Error
)
console
.
log
(
_missionLineViewComponent
.
errorString
())
Item
{
map
.
addMapItem
(
_missionLineViewComponent
)
property
var
_missionLineViewComponent
}
Component.onCompleted
:
{
_missionLineViewComponent
=
missionLineViewComponent
.
createObject
(
map
,
{
"
object
"
:
object
})
if
(
_missionLineViewComponent
.
status
===
Component
.
Error
)
console
.
log
(
_missionLineViewComponent
.
errorString
())
map
.
addMapItem
(
_missionLineViewComponent
)
}
Component.onDestruction
:
{
Component
.
onDestruction
:
{
_missionLineViewComponent
.
destroy
()
_missionLineViewComponent
.
destroy
()
}
}
}
}
Component
{
Component
{
...
@@ -72,9 +64,7 @@ Item {
...
@@ -72,9 +64,7 @@ Item {
line.width
:
3
line.width
:
3
line.color
:
"
#be781c
"
// Hack, can't get palette to work in here
line.color
:
"
#be781c
"
// Hack, can't get palette to work in here
z
:
QGroundControl
.
zOrderWaypointLines
z
:
QGroundControl
.
zOrderWaypointLines
path
:
object
?
[
object
.
coordinate1
,
object
.
coordinate2
]
:
undefined
path
:
_missionController
.
waypointPath
property
var
object
}
}
}
}
}
}
src/MissionManager/CameraSectionTest.cc
View file @
5f0128d3
...
@@ -46,12 +46,15 @@ void CameraSectionTest::init(void)
...
@@ -46,12 +46,15 @@ void CameraSectionTest::init(void)
QVERIFY
(
_spySection
);
QVERIFY
(
_spySection
);
_validGimbalItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_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
),
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
);
this
);
_validTimeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_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
),
MissionItem
(
0
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
48
,
0
,
NAN
,
NAN
,
NAN
,
NAN
,
true
,
false
),
this
);
this
);
_validDistanceItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_validDistanceItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
,
// editMode
MissionItem
(
0
,
MissionItem
(
0
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
...
@@ -62,6 +65,7 @@ void CameraSectionTest::init(void)
...
@@ -62,6 +65,7 @@ void CameraSectionTest::init(void)
true
,
false
),
true
,
false
),
this
);
this
);
_validStartVideoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_validStartVideoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
,
// editMode
MissionItem
(
0
,
// sequence number
MissionItem
(
0
,
// sequence number
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
...
@@ -72,15 +76,19 @@ void CameraSectionTest::init(void)
...
@@ -72,15 +76,19 @@ void CameraSectionTest::init(void)
false
),
// isCurrentItem
false
),
// isCurrentItem
this
);
this
);
_validStopVideoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_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
),
MissionItem
(
0
,
MAV_CMD_VIDEO_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
true
,
false
),
this
);
this
);
_validStopDistanceItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_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
),
MissionItem
(
0
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
),
this
);
this
);
_validStopTimeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_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
),
MissionItem
(
1
,
MAV_CMD_IMAGE_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
true
,
false
),
this
);
this
);
_validCameraPhotoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_validCameraPhotoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
,
// editMode
MissionItem
(
0
,
// sequence number
MissionItem
(
0
,
// sequence number
MAV_CMD_SET_CAMERA_MODE
,
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
...
@@ -91,6 +99,7 @@ void CameraSectionTest::init(void)
...
@@ -91,6 +99,7 @@ void CameraSectionTest::init(void)
false
),
// isCurrentItem
false
),
// isCurrentItem
this
);
this
);
_validCameraVideoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_validCameraVideoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
,
// editMode
MissionItem
(
0
,
// sequence number
MissionItem
(
0
,
// sequence number
MAV_CMD_SET_CAMERA_MODE
,
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
...
@@ -101,6 +110,7 @@ void CameraSectionTest::init(void)
...
@@ -101,6 +110,7 @@ void CameraSectionTest::init(void)
false
),
// isCurrentItem
false
),
// isCurrentItem
this
);
this
);
_validCameraSurveyPhotoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_validCameraSurveyPhotoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
,
// editMode
MissionItem
(
0
,
// sequence number
MissionItem
(
0
,
// sequence number
MAV_CMD_SET_CAMERA_MODE
,
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
...
@@ -111,6 +121,7 @@ void CameraSectionTest::init(void)
...
@@ -111,6 +121,7 @@ void CameraSectionTest::init(void)
false
),
// isCurrentItem
false
),
// isCurrentItem
this
);
this
);
_validTakePhotoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
_validTakePhotoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
,
// editMode
MissionItem
(
0
,
MissionItem
(
0
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
...
@@ -351,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void)
...
@@ -351,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void)
70.1234567
,
70.1234567
,
true
,
// autoContinue
true
,
// autoContinue
false
);
// isCurrentItem
false
);
// isCurrentItem
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_offlineVehicle
,
missionItem
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
/* editMode */
,
missionItem
);
QVERIFY
(
item
->
cameraSection
());
QVERIFY
(
item
->
cameraSection
());
QCOMPARE
(
item
->
cameraSection
()
->
available
(),
false
);
QCOMPARE
(
item
->
cameraSection
()
->
available
(),
false
);
}
}
...
@@ -622,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
...
@@ -622,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Gimbal command but incorrect settings
// 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
invalidSimpleItem
.
missionItem
().
setParam2
(
10
);
// roll is not supported
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -712,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
...
@@ -712,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
*/
*/
// Mode command but incorrect settings
// 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
invalidSimpleItem
.
missionItem
().
setParam3
(
1
);
// Param3 should be NaN
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -751,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
...
@@ -751,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
// Image start command but incorrect settings
// 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
invalidSimpleItem
.
missionItem
().
setParam3
(
10
);
// must be 0 for unlimited
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -792,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
...
@@ -792,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
// Trigger distance command but incorrect settings
// 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
invalidSimpleItem
.
missionItem
().
setParam1
(
-
1
);
// must be >= 0
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -877,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
...
@@ -877,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
// 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)
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
// Reserved (must be 0)
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -920,7 +931,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
...
@@ -920,7 +931,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
// Trigger distance command but incorrect settings
// 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
invalidSimpleItem
.
missionItem
().
setParam1
(
10
);
// must be 0
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
@@ -993,7 +1004,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
...
@@ -993,7 +1004,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
// Take Photo command but incorrect settings
// 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
invalidSimpleItem
.
missionItem
().
setParam3
(
10
);
// must be 1 for single photo
visualItems
.
append
(
&
invalidSimpleItem
);
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
...
...
src/MissionManager/GeoFenceManager.cc
View file @
5f0128d3
...
@@ -99,11 +99,8 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
...
@@ -99,11 +99,8 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
fenceItems
.
append
(
item
);
fenceItems
.
append
(
item
);
}
}
// Plan manager takes control of MissionItems, so no need to delete
_planManager
.
writeMissionItems
(
fenceItems
);
_planManager
.
writeMissionItems
(
fenceItems
);
for
(
int
i
=
0
;
i
<
fenceItems
.
count
();
i
++
)
{
fenceItems
[
i
]
->
deleteLater
();
}
}
}
void
GeoFenceManager
::
removeAll
(
void
)
void
GeoFenceManager
::
removeAll
(
void
)
...
...
src/MissionManager/MissionController.cc
View file @
5f0128d3
...
@@ -175,7 +175,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
...
@@ -175,7 +175,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
for
(;
i
<
newMissionItems
.
count
();
i
++
)
{
for
(;
i
<
newMissionItems
.
count
();
i
++
)
{
const
MissionItem
*
missionItem
=
newMissionItems
[
i
];
const
MissionItem
*
missionItem
=
newMissionItems
[
i
];
newControllerMissionItems
->
append
(
new
SimpleMissionItem
(
_controllerVehicle
,
*
missionItem
,
this
));
newControllerMissionItems
->
append
(
new
SimpleMissionItem
(
_controllerVehicle
,
_editMode
,
*
missionItem
,
this
));
}
}
_deinitAllVisualItems
();
_deinitAllVisualItems
();
...
@@ -313,11 +313,8 @@ void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel*
...
@@ -313,11 +313,8 @@ void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel*
_convertToMissionItems
(
visualMissionItems
,
rgMissionItems
,
vehicle
);
_convertToMissionItems
(
visualMissionItems
,
rgMissionItems
,
vehicle
);
// PlanManager takes control of MissionItems so no need to delete
vehicle
->
missionManager
()
->
writeMissionItems
(
rgMissionItems
);
vehicle
->
missionManager
()
->
writeMissionItems
(
rgMissionItems
);
for
(
int
i
=
0
;
i
<
rgMissionItems
.
count
();
i
++
)
{
rgMissionItems
[
i
]
->
deleteLater
();
}
}
}
}
}
...
@@ -1021,6 +1018,7 @@ void MissionController::_recalcWaypointLines(void)
...
@@ -1021,6 +1018,7 @@ void MissionController::_recalcWaypointLines(void)
CoordVectHashTable
old_table
=
_linesTable
;
CoordVectHashTable
old_table
=
_linesTable
;
_linesTable
.
clear
();
_linesTable
.
clear
();
_waypointLines
.
clear
();
_waypointLines
.
clear
();
_waypointPath
.
clear
();
bool
linkEndToHome
;
bool
linkEndToHome
;
SimpleMissionItem
*
lastItem
=
_visualItems
->
value
<
SimpleMissionItem
*>
(
_visualItems
->
count
()
-
1
);
SimpleMissionItem
*
lastItem
=
_visualItems
->
value
<
SimpleMissionItem
*>
(
_visualItems
->
count
()
-
1
);
...
@@ -1042,22 +1040,33 @@ void MissionController::_recalcWaypointLines(void)
...
@@ -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_TAKEOFF
||
qobject_cast
<
SimpleMissionItem
*>
(
item
)
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_VTOL_TAKEOFF
))
{
qobject_cast
<
SimpleMissionItem
*>
(
item
)
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_VTOL_TAKEOFF
))
{
linkStartToHome
=
true
;
linkStartToHome
=
true
;
if
(
!
_editMode
)
{
_waypointPath
.
append
(
QVariant
::
fromValue
(
lastCoordinateItem
->
coordinate
()));
}
}
}
if
(
item
->
specifiesCoordinate
())
{
if
(
item
->
specifiesCoordinate
())
{
if
(
!
item
->
isStandaloneCoordinate
())
{
if
(
!
item
->
isStandaloneCoordinate
())
{
firstCoordinateItem
=
false
;
firstCoordinateItem
=
false
;
VisualItemPair
pair
(
lastCoordinateItem
,
item
);
if
(
lastCoordinateItem
!=
_settingsItem
||
(
showHomePosition
&&
linkStartToHome
))
{
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
;
lastCoordinateItem
=
item
;
}
}
}
}
}
}
if
(
linkEndToHome
&&
lastCoordinateItem
!=
_settingsItem
&&
showHomePosition
)
{
if
(
linkEndToHome
&&
lastCoordinateItem
!=
_settingsItem
&&
showHomePosition
)
{
VisualItemPair
pair
(
lastCoordinateItem
,
_settingsItem
);
if
(
_editMode
)
{
_addWaypointLineSegment
(
old_table
,
pair
);
VisualItemPair
pair
(
lastCoordinateItem
,
_settingsItem
);
_addWaypointLineSegment
(
old_table
,
pair
);
}
else
{
_waypointPath
.
append
(
QVariant
::
fromValue
(
_settingsItem
->
coordinate
()));
}
}
}
{
{
...
@@ -1077,7 +1086,16 @@ void MissionController::_recalcWaypointLines(void)
...
@@ -1077,7 +1086,16 @@ void MissionController::_recalcWaypointLines(void)
_recalcMissionFlightStatus
();
_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
waypointLinesChanged
();
emit
waypointPathChanged
();
}
}
void
MissionController
::
_updateBatteryInfo
(
int
waypointIndex
)
void
MissionController
::
_updateBatteryInfo
(
int
waypointIndex
)
...
...
src/MissionManager/MissionController.h
View file @
5f0128d3
...
@@ -66,7 +66,8 @@ public:
...
@@ -66,7 +66,8 @@ public:
}
MissionFlightStatus_t
;
}
MissionFlightStatus_t
;
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
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
(
QStringList
complexMissionItemNames
READ
complexMissionItemNames
NOTIFY
complexMissionItemNamesChanged
)
Q_PROPERTY
(
QGeoCoordinate
plannedHomePosition
READ
plannedHomePosition
NOTIFY
plannedHomePositionChanged
)
Q_PROPERTY
(
QGeoCoordinate
plannedHomePosition
READ
plannedHomePosition
NOTIFY
plannedHomePositionChanged
)
...
@@ -146,6 +147,7 @@ public:
...
@@ -146,6 +147,7 @@ public:
QmlObjectListModel
*
visualItems
(
void
)
{
return
_visualItems
;
}
QmlObjectListModel
*
visualItems
(
void
)
{
return
_visualItems
;
}
QmlObjectListModel
*
waypointLines
(
void
)
{
return
&
_waypointLines
;
}
QmlObjectListModel
*
waypointLines
(
void
)
{
return
&
_waypointLines
;
}
QVariantList
waypointPath
(
void
)
{
return
_waypointPath
;
}
QStringList
complexMissionItemNames
(
void
)
const
;
QStringList
complexMissionItemNames
(
void
)
const
;
QGeoCoordinate
plannedHomePosition
(
void
)
const
;
QGeoCoordinate
plannedHomePosition
(
void
)
const
;
VisualMissionItem
*
currentPlanViewItem
(
void
)
const
;
VisualMissionItem
*
currentPlanViewItem
(
void
)
const
;
...
@@ -167,27 +169,28 @@ public:
...
@@ -167,27 +169,28 @@ public:
int
batteriesRequired
(
void
)
const
{
return
_missionFlightStatus
.
batteriesRequired
;
}
///< -1 for not supported
int
batteriesRequired
(
void
)
const
{
return
_missionFlightStatus
.
batteriesRequired
;
}
///< -1 for not supported
signals:
signals:
void
visualItemsChanged
(
void
);
void
visualItemsChanged
(
void
);
void
waypointLinesChanged
(
void
);
void
waypointLinesChanged
(
void
);
void
newItemsFromVehicle
(
void
);
void
waypointPathChanged
(
void
);
void
missionDistanceChanged
(
double
missionDistance
);
void
newItemsFromVehicle
(
void
);
void
missionTimeChanged
(
void
);
void
missionDistanceChanged
(
double
missionDistance
);
void
missionHoverDistanceChanged
(
double
missionHoverDistance
);
void
missionTimeChanged
(
void
);
void
missionHoverTimeChanged
(
void
);
void
missionHoverDistanceChanged
(
double
missionHoverDistance
);
void
missionCruiseDistanceChanged
(
double
missionCruiseDistance
);
void
missionHoverTimeChanged
(
void
);
void
missionCruiseTimeChanged
(
void
);
void
missionCruiseDistanceChanged
(
double
missionCruiseDistance
);
void
missionMaxTelemetryChanged
(
double
missionMaxTelemetry
);
void
missionCruiseTimeChanged
(
void
);
void
complexMissionItemNamesChanged
(
void
);
void
missionMaxTelemetryChanged
(
double
missionMaxTelemetry
);
void
resumeMissionIndexChanged
(
void
);
void
complexMissionItemNamesChanged
(
void
);
void
resumeMissionReady
(
void
);
void
resumeMissionIndexChanged
(
void
);
void
resumeMissionUploadFail
(
void
);
void
resumeMissionReady
(
void
);
void
batteryChangePointChanged
(
int
batteryChangePoint
);
void
resumeMissionUploadFail
(
void
);
void
batteriesRequiredChanged
(
int
batteriesRequired
);
void
batteryChangePointChanged
(
int
batteryChangePoint
);
void
plannedHomePositionChanged
(
QGeoCoordinate
plannedHomePosition
);
void
batteriesRequiredChanged
(
int
batteriesRequired
);
void
progressPctChanged
(
double
progressPct
);
void
plannedHomePositionChanged
(
QGeoCoordinate
plannedHomePosition
);
void
currentMissionIndexChanged
(
int
currentMissionIndex
);
void
progressPctChanged
(
double
progressPct
);
void
currentPlanViewIndexChanged
();
void
currentMissionIndexChanged
(
int
currentMissionIndex
);
void
currentPlanViewItemChanged
();
void
currentPlanViewIndexChanged
(
void
);
void
currentPlanViewItemChanged
(
void
);
private
slots
:
private
slots
:
void
_newMissionItemsAvailableFromVehicle
(
bool
removeAllRequested
);
void
_newMissionItemsAvailableFromVehicle
(
bool
removeAllRequested
);
...
@@ -242,6 +245,7 @@ private:
...
@@ -242,6 +245,7 @@ private:
QmlObjectListModel
*
_visualItems
;
QmlObjectListModel
*
_visualItems
;
MissionSettingsItem
*
_settingsItem
;
MissionSettingsItem
*
_settingsItem
;
QmlObjectListModel
_waypointLines
;
QmlObjectListModel
_waypointLines
;
QVariantList
_waypointPath
;
CoordVectHashTable
_linesTable
;
CoordVectHashTable
_linesTable
;
bool
_firstItemsFromVehicle
;
bool
_firstItemsFromVehicle
;
bool
_itemsRequested
;
bool
_itemsRequested
;
...
...
src/MissionManager/MissionManager.cc
View file @
5f0128d3
...
@@ -214,11 +214,6 @@ void MissionManager::generateResumeMission(int resumeIndex)
...
@@ -214,11 +214,6 @@ void MissionManager::generateResumeMission(int resumeIndex)
}
}
_resumeMission
=
true
;
_resumeMission
=
true
;
_writeMissionItemsWorker
();
_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
/// Called when a new mavlink message for out vehicle is received
...
...
src/MissionManager/PlanManager.cc
View file @
5f0128d3
...
@@ -85,8 +85,8 @@ void PlanManager::writeMissionItems(const QList<MissionItem*>& missionItems)
...
@@ -85,8 +85,8 @@ void PlanManager::writeMissionItems(const QList<MissionItem*>& missionItems)
int
firstIndex
=
skipFirstItem
?
1
:
0
;
int
firstIndex
=
skipFirstItem
?
1
:
0
;
for
(
int
i
=
firstIndex
;
i
<
missionItems
.
count
();
i
++
)
{
for
(
int
i
=
firstIndex
;
i
<
missionItems
.
count
();
i
++
)
{
MissionItem
*
item
=
new
MissionItem
(
*
missionItems
[
i
])
;
MissionItem
*
item
=
missionItems
[
i
]
;
_writeMissionItems
.
append
(
item
);
_writeMissionItems
.
append
(
item
);
// PlanManager takes control of passed MissionItem
item
->
setIsCurrentItem
(
i
==
firstIndex
);
item
->
setIsCurrentItem
(
i
==
firstIndex
);
...
@@ -911,7 +911,8 @@ void PlanManager::removeAll(void)
...
@@ -911,7 +911,8 @@ void PlanManager::removeAll(void)
void
PlanManager
::
_clearAndDeleteMissionItems
(
void
)
void
PlanManager
::
_clearAndDeleteMissionItems
(
void
)
{
{
for
(
int
i
=
0
;
i
<
_missionItems
.
count
();
i
++
)
{
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
();
_missionItems
.
clear
();
}
}
...
@@ -920,7 +921,8 @@ void PlanManager::_clearAndDeleteMissionItems(void)
...
@@ -920,7 +921,8 @@ void PlanManager::_clearAndDeleteMissionItems(void)
void
PlanManager
::
_clearAndDeleteWriteMissionItems
(
void
)
void
PlanManager
::
_clearAndDeleteWriteMissionItems
(
void
)
{
{
for
(
int
i
=
0
;
i
<
_writeMissionItems
.
count
();
i
++
)
{
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
();
_writeMissionItems
.
clear
();
}
}
...
...
src/MissionManager/PlanManager.h
View file @
5f0128d3
...
@@ -47,6 +47,7 @@ public:
...
@@ -47,6 +47,7 @@ public:
void
loadFromVehicle
(
void
);
void
loadFromVehicle
(
void
);
/// Writes the specified set of mission items to the vehicle
/// 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
/// @param missionItems Items to send to vehicle
/// Signals sendComplete when done
/// Signals sendComplete when done
void
writeMissionItems
(
const
QList
<
MissionItem
*>&
missionItems
);
void
writeMissionItems
(
const
QList
<
MissionItem
*>&
missionItems
);
...
...
src/MissionManager/SectionTest.cc
View file @
5f0128d3
...
@@ -37,7 +37,7 @@ void SectionTest::init(void)
...
@@ -37,7 +37,7 @@ void SectionTest::init(void)
70.1234567
,
70.1234567
,
true
,
// autoContinue
true
,
// autoContinue
false
);
// isCurrentItem
false
);
// isCurrentItem
_simpleItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
missionItem
);
_simpleItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
/* editMode */
,
missionItem
);
}
}
void
SectionTest
::
cleanup
(
void
)
void
SectionTest
::
cleanup
(
void
)
...
@@ -77,7 +77,7 @@ void SectionTest::_commonScanTest(Section* section)
...
@@ -77,7 +77,7 @@ void SectionTest::_commonScanTest(Section* section)
QmlObjectListModel
waypointVisualItems
;
QmlObjectListModel
waypointVisualItems
;
MissionItem
waypointItem
(
0
,
MAV_CMD_NAV_WAYPOINT
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
);
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
);
waypointVisualItems
.
append
(
&
simpleItem
);
waypointVisualItems
.
append
(
&
simpleItem
);
waypointVisualItems
.
append
(
&
simpleItem
);
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
5f0128d3
...
@@ -85,7 +85,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
...
@@ -85,7 +85,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
connect
(
this
,
&
SimpleMissionItem
::
cameraSectionChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
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
)
:
VisualMissionItem
(
vehicle
,
parent
)
,
_missionItem
(
missionItem
)
,
_missionItem
(
missionItem
)
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
...
@@ -111,11 +111,16 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
...
@@ -111,11 +111,16 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
_altitudeRelativeToHomeFact
.
setRawValue
(
true
);
_altitudeRelativeToHomeFact
.
setRawValue
(
true
);
_isCurrentItem
=
missionItem
.
isCurrentItem
();
_isCurrentItem
=
missionItem
.
isCurrentItem
();
_setupMetaData
();
// In !editMode we skip some of the intialization to save memory
if
(
editMode
)
{
_setupMetaData
();
}
_connectSignals
();
_connectSignals
();
_updateOptionalSections
();
_updateOptionalSections
();
_syncFrameToAltitudeRelativeToHome
();
_syncFrameToAltitudeRelativeToHome
();
_rebuildFacts
();
if
(
editMode
)
{
_rebuildFacts
();
}
}
}
SimpleMissionItem
::
SimpleMissionItem
(
const
SimpleMissionItem
&
other
,
QObject
*
parent
)
SimpleMissionItem
::
SimpleMissionItem
(
const
SimpleMissionItem
&
other
,
QObject
*
parent
)
...
...
src/MissionManager/SimpleMissionItem.h
View file @
5f0128d3
...
@@ -24,7 +24,7 @@ class SimpleMissionItem : public VisualMissionItem
...
@@ -24,7 +24,7 @@ class SimpleMissionItem : public VisualMissionItem
public:
public:
SimpleMissionItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
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
(
const
SimpleMissionItem
&
other
,
QObject
*
parent
=
NULL
);
~
SimpleMissionItem
();
~
SimpleMissionItem
();
...
...
src/MissionManager/SimpleMissionItemTest.cc
View file @
5f0128d3
...
@@ -100,7 +100,7 @@ void SimpleMissionItemTest::init(void)
...
@@ -100,7 +100,7 @@ void SimpleMissionItemTest::init(void)
70.1234567
,
70.1234567
,
true
,
// autoContinue
true
,
// autoContinue
false
);
// isCurrentItem
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 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
// 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)
...
@@ -139,7 +139,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
70.1234567
,
70.1234567
,
true
,
// autoContinue
true
,
// autoContinue
false
);
// isCurrentItem
false
);
// isCurrentItem
SimpleMissionItem
simpleMissionItem
(
vehicle
,
missionItem
);
SimpleMissionItem
simpleMissionItem
(
vehicle
,
true
/* editMode */
,
missionItem
);
// Validate that the fact values are correctly returned
// Validate that the fact values are correctly returned
...
...
src/MissionManager/SpeedSectionTest.cc
View file @
5f0128d3
...
@@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void)
...
@@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void)
70.1234567
,
70.1234567
,
true
,
// autoContinue
true
,
// autoContinue
false
);
// isCurrentItem
false
);
// isCurrentItem
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_offlineVehicle
,
missionItem
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_offlineVehicle
,
true
/* editMode */
,
missionItem
);
QVERIFY
(
item
->
speedSection
());
QVERIFY
(
item
->
speedSection
());
QCOMPARE
(
item
->
speedSection
()
->
available
(),
false
);
QCOMPARE
(
item
->
speedSection
()
->
available
(),
false
);
}
}
...
@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
...
@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
double
flightSpeed
=
10.123456
;
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
);
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
();
MissionItem
&
simpleMissionItem
=
simpleItem
.
missionItem
();
visualItems
.
append
(
&
simpleItem
);
visualItems
.
append
(
&
simpleItem
);
scanIndex
=
0
;
scanIndex
=
0
;
...
@@ -265,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void)
...
@@ -265,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Valid item in wrong position
// Valid item in wrong position
QmlObjectListModel
waypointVisualItems
;
QmlObjectListModel
waypointVisualItems
;
MissionItem
waypointMissionItem
(
0
,
MAV_CMD_NAV_WAYPOINT
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
);
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
;
simpleMissionItem
=
validSpeedItem
;
visualItems
.
append
(
&
simpleWaypointItem
);
visualItems
.
append
(
&
simpleWaypointItem
);
visualItems
.
append
(
&
simpleMissionItem
);
visualItems
.
append
(
&
simpleMissionItem
);
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment