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
513d2cd8
Unverified
Commit
513d2cd8
authored
Nov 14, 2019
by
Don Gagne
Committed by
GitHub
Nov 14, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #8041 from DonLakeFlyer/LandTool
Plan: Land tool
parents
07934419
5ad945af
Changes
10
Show whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
184 additions
and
242 deletions
+184
-242
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+1
-1
CorridorScanPlanCreator.cc
src/MissionManager/CorridorScanPlanCreator.cc
+2
-10
MissionController.cc
src/MissionManager/MissionController.cc
+154
-121
MissionController.h
src/MissionManager/MissionController.h
+11
-0
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+2
-43
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+0
-6
StructureScanPlanCreator.cc
src/MissionManager/StructureScanPlanCreator.cc
+1
-9
SurveyPlanCreator.cc
src/MissionManager/SurveyPlanCreator.cc
+2
-10
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+0
-22
PlanView.qml
src/PlanView/PlanView.qml
+11
-20
No files found.
src/FlightDisplay/GuidedActionsController.qml
View file @
513d2cd8
...
...
@@ -36,7 +36,7 @@ Item {
readonly
property
string
emergencyStopTitle
:
qsTr
(
"
EMERGENCY STOP
"
)
readonly
property
string
armTitle
:
qsTr
(
"
Arm
"
)
readonly
property
string
disarmTitle
:
qsTr
(
"
Disarm
"
)
readonly
property
string
rtlTitle
:
qsTr
(
"
R
TL
"
)
readonly
property
string
rtlTitle
:
qsTr
(
"
R
eturn
"
)
readonly
property
string
takeoffTitle
:
qsTr
(
"
Takeoff
"
)
readonly
property
string
landTitle
:
qsTr
(
"
Land
"
)
readonly
property
string
startMissionTitle
:
qsTr
(
"
Start Mission
"
)
...
...
src/MissionManager/CorridorScanPlanCreator.cc
View file @
513d2cd8
...
...
@@ -22,15 +22,7 @@ void CorridorScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController
->
removeAll
();
VisualMissionItem
*
takeoffItem
=
_missionController
->
insertTakeoffItem
(
mapCenterCoord
,
-
1
);
takeoffItem
->
setWizardMode
(
true
);
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternCorridorScanName
,
mapCenterCoord
,
-
1
)
->
setWizardMode
(
true
);
if
(
_planMasterController
->
managerVehicle
()
->
fixedWing
())
{
FixedWingLandingComplexItem
*
landingItem
=
qobject_cast
<
FixedWingLandingComplexItem
*>
(
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternFWLandingName
,
mapCenterCoord
,
-
1
));
landingItem
->
setWizardMode
(
true
);
landingItem
->
setLoiterDragAngleOnly
(
true
);
}
else
{
MissionSettingsItem
*
settingsItem
=
_missionController
->
visualItems
()
->
value
<
MissionSettingsItem
*>
(
0
);
settingsItem
->
setMissionEndRTL
(
true
);
}
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternCorridorScanName
,
mapCenterCoord
,
-
1
);
_missionController
->
insertLandItem
(
mapCenterCoord
,
-
1
);
_missionController
->
setCurrentPlanViewIndex
(
takeoffItem
->
sequenceNumber
(),
true
);
}
src/MissionManager/MissionController.cc
View file @
513d2cd8
...
...
@@ -351,13 +351,13 @@ int MissionController::_nextSequenceNumber(void)
}
}
VisualMissionItem
*
MissionController
::
insertSimpleMissionItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
VisualMissionItem
*
MissionController
::
_insertSimpleMissionItemWorker
(
QGeoCoordinate
coordinate
,
MAV_CMD
command
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
int
sequenceNumber
=
_nextSequenceNumber
();
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_controllerVehicle
,
_flyView
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCoordinate
(
coordinate
);
newItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
newItem
->
setCommand
(
command
);
_initVisualItem
(
newItem
);
if
(
newItem
->
specifiesAltitude
())
{
...
...
@@ -386,6 +386,12 @@ VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coo
return
newItem
;
}
VisualMissionItem
*
MissionController
::
insertSimpleMissionItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
return
_insertSimpleMissionItemWorker
(
coordinate
,
MAV_CMD_NAV_WAYPOINT
,
visualItemIndex
,
makeCurrentItem
);
}
VisualMissionItem
*
MissionController
::
insertTakeoffItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
int
sequenceNumber
=
_nextSequenceNumber
();
...
...
@@ -423,49 +429,29 @@ VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate coordinat
return
newItem
;
}
VisualMissionItem
*
MissionController
::
insert
ROIMission
Item
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
VisualMissionItem
*
MissionController
::
insert
Land
Item
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
int
sequenceNumber
=
_nextSequenceNumber
();
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_controllerVehicle
,
_flyView
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCommand
((
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
MAV_CMD_DO_SET_ROI_LOCATION
)
?
MAV_CMD_DO_SET_ROI_LOCATION
:
MAV_CMD_DO_SET_ROI
));
_initVisualItem
(
newItem
);
newItem
->
setCoordinate
(
coordinate
);
double
prevAltitude
;
int
prevAltitudeMode
;
if
(
_findPreviousAltitude
(
visualItemIndex
,
&
prevAltitude
,
&
prevAltitudeMode
))
{
newItem
->
altitude
()
->
setRawValue
(
prevAltitude
);
newItem
->
setAltitudeMode
(
static_cast
<
QGroundControlQmlGlobal
::
AltitudeMode
>
(
prevAltitudeMode
));
}
if
(
visualItemIndex
==
-
1
)
{
_visualItems
->
append
(
newItem
);
if
(
_managerVehicle
->
fixedWing
())
{
FixedWingLandingComplexItem
*
fwLanding
=
qobject_cast
<
FixedWingLandingComplexItem
*>
(
insertComplexMissionItem
(
MissionController
::
patternFWLandingName
,
coordinate
,
visualItemIndex
,
makeCurrentItem
));
fwLanding
->
setLoiterDragAngleOnly
(
true
);
return
fwLanding
;
}
else
{
_visualItems
->
insert
(
visualItemIndex
,
newItem
);
}
_recalcAll
();
if
(
makeCurrentItem
)
{
setCurrentPlanViewIndex
(
newItem
->
sequenceNumber
(),
true
);
return
_insertSimpleMissionItemWorker
(
coordinate
,
MAV_CMD_NAV_RETURN_TO_LAUNCH
,
visualItemIndex
,
makeCurrentItem
);
}
}
return
newItem
;
VisualMissionItem
*
MissionController
::
insertROIMissionItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
MAV_CMD
command
=
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
MAV_CMD_DO_SET_ROI_LOCATION
)
?
MAV_CMD_DO_SET_ROI_LOCATION
:
MAV_CMD_DO_SET_ROI
;
return
_insertSimpleMissionItemWorker
(
coordinate
,
command
,
visualItemIndex
,
makeCurrentItem
);
}
VisualMissionItem
*
MissionController
::
insertComplexMissionItem
(
QString
itemName
,
QGeoCoordinate
mapCenterCoordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
ComplexMissionItem
*
newItem
=
nullptr
;
// If the ComplexMissionItem is inserted first, add a TakeOff SimpleMissionItem
if
(
_visualItems
->
count
()
==
1
&&
(
_controllerVehicle
->
fixedWing
()
||
_controllerVehicle
->
vtol
()
||
_controllerVehicle
->
multiRotor
()))
{
insertSimpleMissionItem
(
mapCenterCoordinate
,
visualItemIndex
);
visualItemIndex
++
;
}
if
(
itemName
==
patternSurveyName
)
{
newItem
=
new
SurveyComplexItem
(
_controllerVehicle
,
_flyView
,
QString
()
/* kmlFile */
,
_visualItems
/* parent */
);
newItem
->
setCoordinate
(
mapCenterCoordinate
);
...
...
@@ -539,6 +525,7 @@ void MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* comp
}
complexItem
->
setSequenceNumber
(
sequenceNumber
);
complexItem
->
setWizardMode
(
true
);
_initVisualItem
(
complexItem
);
if
(
visualItemIndex
==
-
1
)
{
...
...
@@ -1168,11 +1155,13 @@ CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable&
void
MissionController
::
_recalcWaypointLines
(
void
)
{
int
segmentCount
=
0
;
VisualItemPair
lastSegmentVisualItemPair
;
bool
firstCoordinateItem
=
true
;
VisualMissionItem
*
lastCoordinateItem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
int
segmentCount
=
0
;
bool
firstCoordinateNotFound
=
true
;
VisualMissionItem
*
lastCoordinateItemBeforeRTL
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
bool
linkEndToHome
=
false
;
bool
linkStartToHome
=
_managerVehicle
->
rover
()
?
true
:
false
;
bool
foundRTL
=
false
;
bool
homePositionValid
=
_settingsItem
->
coordinate
().
isValid
();
qCDebug
(
MissionControllerLog
)
<<
"_recalcWaypointLines homePositionValid"
<<
homePositionValid
;
...
...
@@ -1188,32 +1177,44 @@ void MissionController::_recalcWaypointLines(void)
_waypointLines
.
clear
();
_directionArrows
.
clear
();
bool
linkEndToHome
;
SimpleMissionItem
*
lastItem
=
_visualItems
->
value
<
SimpleMissionItem
*>
(
_visualItems
->
count
()
-
1
);
if
(
lastItem
&&
(
int
)
lastItem
->
command
()
==
MAV_CMD_NAV_RETURN_TO_LAUNCH
)
{
linkEndToHome
=
true
;
}
else
{
linkEndToHome
=
_settingsItem
->
missionEndRTL
();
}
// Grovel through the list of items keeping track of things needed to correctly draw waypoints lines
bool
linkStartToHome
=
false
;
for
(
int
i
=
1
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
VisualMissionItem
*
visualItem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
);
if
(
simpleItem
)
{
MAV_CMD
command
=
simpleItem
->
mavCommand
();
switch
(
command
)
{
case
MAV_CMD_NAV_TAKEOFF
:
case
MAV_CMD_NAV_VTOL_TAKEOFF
:
if
(
!
linkEndToHome
)
{
// If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
// Link the first item back to home to show that.
if
(
firstCoordinateItem
&&
item
->
isSimpleItem
())
{
MAV_CMD
command
=
(
MAV_CMD
)
qobject_cast
<
SimpleMissionItem
*>
(
item
)
->
command
();
if
(
command
==
MAV_CMD_NAV_TAKEOFF
||
command
==
MAV_CMD_NAV_VTOL_TAKEOFF
)
{
if
(
firstCoordinateNotFound
)
{
linkStartToHome
=
true
;
}
}
break
;
case
MAV_CMD_NAV_RETURN_TO_LAUNCH
:
linkEndToHome
=
true
;
foundRTL
=
true
;
break
;
default:
break
;
}
}
// No need to add waypoint segments after an RTL.
if
(
foundRTL
)
{
break
;
}
if
(
item
->
specifiesCoordinate
()
&&
!
i
tem
->
isStandaloneCoordinate
())
{
if
(
lastCoordinateItem
!=
_settingsItem
||
(
homePositionValid
&&
linkStartToHome
))
{
if
(
visualItem
->
specifiesCoordinate
()
&&
!
visualI
tem
->
isStandaloneCoordinate
())
{
if
(
lastCoordinateItem
BeforeRTL
!=
_settingsItem
||
(
homePositionValid
&&
linkStartToHome
))
{
// Direction arrows are added to the first segment and every 5 segments in the middle.
bool
addDirectionArrow
=
false
;
if
(
firstCoordinate
Item
||
!
lastCoordinateItem
->
isSimpleItem
()
||
!
i
tem
->
isSimpleItem
())
{
if
(
firstCoordinate
NotFound
||
!
lastCoordinateItemBeforeRTL
->
isSimpleItem
()
||
!
visualI
tem
->
isSimpleItem
())
{
addDirectionArrow
=
true
;
}
else
if
(
segmentCount
>
5
)
{
segmentCount
=
0
;
...
...
@@ -1221,7 +1222,7 @@ void MissionController::_recalcWaypointLines(void)
}
segmentCount
++
;
lastSegmentVisualItemPair
=
VisualItemPair
(
lastCoordinateItem
,
i
tem
);
lastSegmentVisualItemPair
=
VisualItemPair
(
lastCoordinateItem
BeforeRTL
,
visualI
tem
);
if
(
!
_flyView
||
addDirectionArrow
)
{
CoordinateVector
*
coordVector
=
_addWaypointLineSegment
(
old_table
,
lastSegmentVisualItemPair
);
if
(
addDirectionArrow
)
{
...
...
@@ -1229,9 +1230,9 @@ void MissionController::_recalcWaypointLines(void)
}
}
}
firstCoordinate
Item
=
false
;
_waypointPath
.
append
(
QVariant
::
fromValue
(
i
tem
->
coordinate
()));
lastCoordinateItem
=
i
tem
;
firstCoordinate
NotFound
=
false
;
_waypointPath
.
append
(
QVariant
::
fromValue
(
visualI
tem
->
coordinate
()));
lastCoordinateItem
BeforeRTL
=
visualI
tem
;
}
}
...
...
@@ -1239,8 +1240,8 @@ void MissionController::_recalcWaypointLines(void)
_waypointPath
.
prepend
(
QVariant
::
fromValue
(
_settingsItem
->
coordinate
()));
}
if
(
linkEndToHome
&&
lastCoordinateItem
!=
_settingsItem
&&
homePositionValid
)
{
lastSegmentVisualItemPair
=
VisualItemPair
(
lastCoordinateItem
,
_settingsItem
);
if
(
linkEndToHome
&&
lastCoordinateItem
BeforeRTL
!=
_settingsItem
&&
homePositionValid
)
{
lastSegmentVisualItemPair
=
VisualItemPair
(
lastCoordinateItem
BeforeRTL
,
_settingsItem
);
if
(
_flyView
)
{
_waypointPath
.
append
(
QVariant
::
fromValue
(
_settingsItem
->
coordinate
()));
}
...
...
@@ -1367,9 +1368,9 @@ void MissionController::_recalcMissionFlightStatus()
}
bool
firstCoordinateItem
=
true
;
VisualMissionItem
*
lastCoordinateItem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
VisualMissionItem
*
lastCoordinateItem
BeforeRTL
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
bool
showHomePosition
=
_settingsItem
->
coordinate
().
isValid
();
bool
homePositionValid
=
_settingsItem
->
coordinate
().
isValid
();
qCDebug
(
MissionControllerLog
)
<<
"_recalcMissionFlightStatus"
;
...
...
@@ -1378,9 +1379,9 @@ void MissionController::_recalcMissionFlightStatus()
// both relative altitude.
// No values for first item
lastCoordinateItem
->
setAltDifference
(
0.0
);
lastCoordinateItem
->
setAzimuth
(
0.0
);
lastCoordinateItem
->
setDistance
(
0.0
);
lastCoordinateItem
BeforeRTL
->
setAltDifference
(
0.0
);
lastCoordinateItem
BeforeRTL
->
setAzimuth
(
0.0
);
lastCoordinateItem
BeforeRTL
->
setDistance
(
0.0
);
double
minAltSeen
=
0.0
;
double
maxAltSeen
=
0.0
;
...
...
@@ -1391,22 +1392,17 @@ void MissionController::_recalcMissionFlightStatus()
bool
vtolInHover
=
true
;
bool
linkStartToHome
=
false
;
bool
linkEndToHome
=
false
;
if
(
showHomePosition
)
{
SimpleMissionItem
*
lastItem
=
_visualItems
->
value
<
SimpleMissionItem
*>
(
_visualItems
->
count
()
-
1
);
if
(
lastItem
&&
(
int
)
lastItem
->
command
()
==
MAV_CMD_NAV_RETURN_TO_LAUNCH
)
{
linkEndToHome
=
true
;
}
else
{
linkEndToHome
=
_settingsItem
->
missionEndRTL
();
}
}
bool
foundRTL
=
false
;
for
(
int
i
=
0
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
item
);
ComplexMissionItem
*
complexItem
=
qobject_cast
<
ComplexMissionItem
*>
(
item
);
if
(
simpleItem
&&
simpleItem
->
mavCommand
()
==
MAV_CMD_NAV_RETURN_TO_LAUNCH
)
{
foundRTL
=
true
;
}
// Assume the worst
item
->
setAzimuth
(
0.0
);
item
->
setDistance
(
0.0
);
...
...
@@ -1443,9 +1439,14 @@ void MissionController::_recalcMissionFlightStatus()
continue
;
}
if
(
foundRTL
)
{
// No more vehicle distances after RTL
continue
;
}
// Link back to home if first item is takeoff and we have home position
if
(
firstCoordinateItem
&&
simpleItem
&&
(
simpleItem
->
command
()
==
MAV_CMD_NAV_TAKEOFF
||
simpleItem
->
c
ommand
()
==
MAV_CMD_NAV_VTOL_TAKEOFF
))
{
if
(
showHomePosition
)
{
if
(
firstCoordinateItem
&&
simpleItem
&&
(
simpleItem
->
mavCommand
()
==
MAV_CMD_NAV_TAKEOFF
||
simpleItem
->
mavC
ommand
()
==
MAV_CMD_NAV_VTOL_TAKEOFF
))
{
if
(
homePositionValid
)
{
linkStartToHome
=
true
;
if
(
_controllerVehicle
->
multiRotor
()
||
_controllerVehicle
->
vtol
())
{
// We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
...
...
@@ -1509,16 +1510,16 @@ void MissionController::_recalcMissionFlightStatus()
firstCoordinateItem
=
false
;
// Update vehicle yaw assuming direction to next waypoint
if
(
item
!=
lastCoordinateItem
)
{
_missionFlightStatus
.
vehicleYaw
=
lastCoordinateItem
->
exitCoordinate
().
azimuthTo
(
item
->
coordinate
());
lastCoordinateItem
->
setMissionVehicleYaw
(
_missionFlightStatus
.
vehicleYaw
);
if
(
item
!=
lastCoordinateItem
BeforeRTL
)
{
_missionFlightStatus
.
vehicleYaw
=
lastCoordinateItem
BeforeRTL
->
exitCoordinate
().
azimuthTo
(
item
->
coordinate
());
lastCoordinateItem
BeforeRTL
->
setMissionVehicleYaw
(
_missionFlightStatus
.
vehicleYaw
);
}
if
(
lastCoordinateItem
!=
_settingsItem
||
linkStartToHome
)
{
if
(
lastCoordinateItem
BeforeRTL
!=
_settingsItem
||
linkStartToHome
)
{
// This is a subsequent waypoint or we are forcing the first waypoint back to home
double
azimuth
,
distance
,
altDifference
;
_calcPrevWaypointValues
(
homePositionAltitude
,
item
,
lastCoordinateItem
,
&
azimuth
,
&
distance
,
&
altDifference
);
_calcPrevWaypointValues
(
homePositionAltitude
,
item
,
lastCoordinateItem
BeforeRTL
,
&
azimuth
,
&
distance
,
&
altDifference
);
item
->
setAltDifference
(
altDifference
);
item
->
setAzimuth
(
azimuth
);
item
->
setDistance
(
distance
);
...
...
@@ -1543,15 +1544,16 @@ void MissionController::_recalcMissionFlightStatus()
item
->
setMissionFlightStatus
(
_missionFlightStatus
);
lastCoordinateItem
=
item
;
lastCoordinateItem
BeforeRTL
=
item
;
}
}
}
lastCoordinateItem
->
setMissionVehicleYaw
(
_missionFlightStatus
.
vehicleYaw
);
lastCoordinateItem
BeforeRTL
->
setMissionVehicleYaw
(
_missionFlightStatus
.
vehicleYaw
);
if
(
linkEndToHome
&&
lastCoordinateItem
!=
_settingsItem
)
{
// Add the information for the final segment back to home
if
(
foundRTL
&&
lastCoordinateItemBeforeRTL
!=
_settingsItem
&&
homePositionValid
)
{
double
azimuth
,
distance
,
altDifference
;
_calcPrevWaypointValues
(
homePositionAltitude
,
lastCoordinateItem
,
_settingsItem
,
&
azimuth
,
&
distance
,
&
altDifference
);
_calcPrevWaypointValues
(
homePositionAltitude
,
lastCoordinateItem
BeforeRTL
,
_settingsItem
,
&
azimuth
,
&
distance
,
&
altDifference
);
// Calculate time/distance
double
hoverTime
=
distance
/
_missionFlightStatus
.
hoverSpeed
;
...
...
@@ -1710,7 +1712,6 @@ void MissionController::_initAllVisualItems(void)
_settingsItem
->
setHomePositionFromVehicle
(
_managerVehicle
);
connect
(
_settingsItem
,
&
MissionSettingsItem
::
coordinateChanged
,
this
,
&
MissionController
::
_recalcAll
);
connect
(
_settingsItem
,
&
MissionSettingsItem
::
missionEndRTLChanged
,
this
,
&
MissionController
::
_recalcAll
);
connect
(
_settingsItem
,
&
MissionSettingsItem
::
coordinateChanged
,
this
,
&
MissionController
::
plannedHomePositionChanged
);
for
(
int
i
=
0
;
i
<
_visualItems
->
count
();
i
++
)
{
...
...
@@ -2078,9 +2079,6 @@ QStringList MissionController::complexMissionItemNames(void) const
complexItems
.
append
(
patternSurveyName
);
complexItems
.
append
(
patternCorridorScanName
);
if
(
_controllerVehicle
->
fixedWing
())
{
complexItems
.
append
(
patternFWLandingName
);
}
if
(
_controllerVehicle
->
multiRotor
()
||
_controllerVehicle
->
vtol
())
{
complexItems
.
append
(
patternStructureScanName
);
}
...
...
@@ -2183,10 +2181,14 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const
void
MissionController
::
setCurrentPlanViewIndex
(
int
sequenceNumber
,
bool
force
)
{
if
(
_visualItems
&&
(
force
||
sequenceNumber
!=
_currentPlanViewIndex
))
{
bool
foundLand
=
false
;
int
takeoffIndex
=
-
1
;
_splitSegment
=
nullptr
;
_currentPlanViewItem
=
nullptr
;
_currentPlanViewIndex
=
-
1
;
_isInsertTakeoffValid
=
true
;
_isInsertLandValid
=
true
;
for
(
int
i
=
0
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
pVI
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
...
...
@@ -2199,10 +2201,31 @@ void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
}
if
(
qobject_cast
<
TakeoffMissionItem
*>
(
pVI
))
{
// Already contains a takeoff command
takeoffIndex
=
i
;
_isInsertTakeoffValid
=
false
;
}
if
(
!
foundLand
)
{
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
pVI
);
if
(
simpleItem
)
{
switch
(
simpleItem
->
mavCommand
())
{
case
MAV_CMD_NAV_LAND
:
case
MAV_CMD_NAV_VTOL_LAND
:
case
MAV_CMD_DO_LAND_START
:
case
MAV_CMD_NAV_RETURN_TO_LAUNCH
:
foundLand
=
true
;
break
;
default:
break
;
}
}
else
{
FixedWingLandingComplexItem
*
fwLanding
=
qobject_cast
<
FixedWingLandingComplexItem
*>
(
pVI
);
if
(
fwLanding
)
{
foundLand
=
true
;
}
}
}
if
(
pVI
->
sequenceNumber
()
==
sequenceNumber
)
{
pVI
->
setIsCurrentItem
(
true
);
_currentPlanViewItem
=
pVI
;
...
...
@@ -2225,10 +2248,20 @@ void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
}
}
if
(
takeoffIndex
!=
-
1
&&
sequenceNumber
<=
takeoffIndex
)
{
// Takeoff item was found which means mission starts from ground.
// Land is only valid after the takeoff item.
_isInsertLandValid
=
false
;
}
else
if
(
foundLand
)
{
// Can't have to land sequences
_isInsertLandValid
=
false
;
}
emit
currentPlanViewIndexChanged
();
emit
currentPlanViewItemChanged
();
emit
splitSegmentChanged
();
emit
isInsertTakeoffValidChanged
();
emit
isInsertLandValidChanged
();
}
}
...
...
src/MissionManager/MissionController.h
View file @
513d2cd8
...
...
@@ -93,6 +93,7 @@ public:
Q_PROPERTY
(
QString
corridorScanComplexItemName
READ
corridorScanComplexItemName
CONSTANT
)
Q_PROPERTY
(
QString
structureScanComplexItemName
READ
structureScanComplexItemName
CONSTANT
)
Q_PROPERTY
(
bool
isInsertTakeoffValid
MEMBER
_isInsertTakeoffValid
NOTIFY
isInsertTakeoffValidChanged
)
///< true: Takeoff tool should be enabled
Q_PROPERTY
(
bool
isInsertLandValid
MEMBER
_isInsertLandValid
NOTIFY
isInsertLandValidChanged
)
///< true: Land tool should be enabled
Q_INVOKABLE
void
removeMissionItem
(
int
index
);
...
...
@@ -110,6 +111,13 @@ public:
/// @return Newly created item
Q_INVOKABLE
VisualMissionItem
*
insertTakeoffItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
=
false
);
/// Add a new land item to the list
/// @param coordinate: Coordinate for item
/// @param visualItemIndex: index to insert at, -1 for end of list
/// @param makeCurrentItem: true: Make this item the current item
/// @return Newly created item
Q_INVOKABLE
VisualMissionItem
*
insertLandItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
=
false
);
/// Add a new ROI mission item to the list
/// @param coordinate: Coordinate for item
/// @param visualItemIndex: index to insert at, -1 for end of list
...
...
@@ -245,6 +253,7 @@ signals:
void
missionBoundingCubeChanged
(
void
);
void
missionItemCountChanged
(
int
missionItemCount
);
void
isInsertTakeoffValidChanged
(
void
);
void
isInsertLandValidChanged
(
void
);
private
slots
:
void
_newMissionItemsAvailableFromVehicle
(
bool
removeAllRequested
);
...
...
@@ -296,6 +305,7 @@ private:
void
_initLoadedVisualItems
(
QmlObjectListModel
*
loadedVisualItems
);
CoordinateVector
*
_addWaypointLineSegment
(
CoordVectHashTable
&
prevItemPairHashTable
,
VisualItemPair
&
pair
);
void
_addTimeDistance
(
bool
vtolInHover
,
double
hoverTime
,
double
cruiseTime
,
double
extraTime
,
double
distance
,
int
seqNum
);
VisualMissionItem
*
_insertSimpleMissionItemWorker
(
QGeoCoordinate
coordinate
,
MAV_CMD
command
,
int
visualItemIndex
,
bool
makeCurrentItem
);
void
_insertComplexMissionItemWorker
(
ComplexMissionItem
*
complexItem
,
int
visualItemIndex
,
bool
makeCurrentItem
);
void
_warnIfTerrainFrameUsed
(
void
);
...
...
@@ -321,6 +331,7 @@ private:
QGeoCoordinate
_takeoffCoordinate
;
CoordinateVector
*
_splitSegment
;
bool
_isInsertTakeoffValid
=
true
;
bool
_isInsertLandValid
=
true
;
static
const
char
*
_settingsGroup
;
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
513d2cd8
...
...
@@ -45,7 +45,6 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject
_speedSection
.
setAvailable
(
true
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
this
,
&
MissionSettingsItem
::
missionEndRTLChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_speedSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
...
...
@@ -155,26 +154,9 @@ void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject
_speedSection
.
appendSectionItems
(
items
,
missionItemParent
,
seqNum
);
}
bool
MissionSettingsItem
::
addMissionEndAction
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QObject
*
missionItemParent
)
bool
MissionSettingsItem
::
addMissionEndAction
(
QList
<
MissionItem
*>&
/*items*/
,
int
/*seqNum*/
,
QObject
*
/*missionItemParent*/
)
{
MissionItem
*
item
=
nullptr
;
// IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
if
(
_missionEndRTL
)
{
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Appending end action RTL seqNum"
<<
seqNum
;
item
=
new
MissionItem
(
seqNum
,
MAV_CMD_NAV_RETURN_TO_LAUNCH
,
MAV_FRAME_MISSION
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
// param 1-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
return
true
;
}
else
{
return
false
;
}
}
bool
MissionSettingsItem
::
scanForMissionSettings
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
)
...
...
@@ -188,21 +170,6 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
foundCameraSection
=
_cameraSection
.
scanForSection
(
visualItems
,
scanIndex
);
foundSpeedSection
=
_speedSection
.
scanForSection
(
visualItems
,
scanIndex
);
// Look at the end of the mission for end actions
int
lastIndex
=
visualItems
->
count
()
-
1
;
SimpleMissionItem
*
item
=
visualItems
->
value
<
SimpleMissionItem
*>
(
lastIndex
);
if
(
item
)
{
MissionItem
&
missionItem
=
item
->
missionItem
();
if
(
missionItem
.
command
()
==
MAV_CMD_NAV_RETURN_TO_LAUNCH
&&
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Scan: Found end action RTL"
;
_missionEndRTL
=
true
;
visualItems
->
removeAt
(
lastIndex
)
->
deleteLater
();
}
}
return
foundSpeedSection
||
foundCameraSection
;
}
...
...
@@ -307,14 +274,6 @@ double MissionSettingsItem::specifiedFlightSpeed(void)
}
}
void
MissionSettingsItem
::
setMissionEndRTL
(
bool
missionEndRTL
)
{
if
(
missionEndRTL
!=
_missionEndRTL
)
{
_missionEndRTL
=
missionEndRTL
;
emit
missionEndRTLChanged
(
missionEndRTL
);
}
}
void
MissionSettingsItem
::
_setHomeAltFromTerrain
(
double
terrainAltitude
)
{
if
(
!
_plannedHomePositionFromVehicle
&&
!
qIsNaN
(
terrainAltitude
))
{
...
...
src/MissionManager/MissionSettingsItem.h
View file @
513d2cd8
...
...
@@ -27,17 +27,13 @@ public:
MissionSettingsItem
(
Vehicle
*
vehicle
,
bool
flyView
,
QObject
*
parent
);
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
bool
missionEndRTL
READ
missionEndRTL
WRITE
setMissionEndRTL
NOTIFY
missionEndRTLChanged
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
CONSTANT
)
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
bool
missionEndRTL
(
void
)
const
{
return
_missionEndRTL
;
}
CameraSection
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
SpeedSection
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
void
setMissionEndRTL
(
bool
missionEndRTL
);
/// Scans the loaded items for settings items
bool
scanForMissionSettings
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
...
...
@@ -96,7 +92,6 @@ public:
signals:
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
missionEndRTLChanged
(
bool
missionEndRTL
);
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
...
...
@@ -112,7 +107,6 @@ private:
int
_sequenceNumber
=
0
;
bool
_plannedHomePositionFromVehicle
=
false
;
bool
_plannedHomePositionMovedByUser
=
false
;
bool
_missionEndRTL
=
false
;
CameraSection
_cameraSection
;
SpeedSection
_speedSection
;
...
...
src/MissionManager/StructureScanPlanCreator.cc
View file @
513d2cd8
...
...
@@ -22,15 +22,7 @@ void StructureScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController
->
removeAll
();
VisualMissionItem
*
takeoffItem
=
_missionController
->
insertTakeoffItem
(
mapCenterCoord
,
-
1
);
takeoffItem
->
setWizardMode
(
true
);
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternStructureScanName
,
mapCenterCoord
,
-
1
)
->
setWizardMode
(
true
);
if
(
_planMasterController
->
managerVehicle
()
->
fixedWing
())
{
FixedWingLandingComplexItem
*
landingItem
=
qobject_cast
<
FixedWingLandingComplexItem
*>
(
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternFWLandingName
,
mapCenterCoord
,
-
1
));
landingItem
->
setWizardMode
(
true
);
landingItem
->
setLoiterDragAngleOnly
(
true
);
}
else
{
MissionSettingsItem
*
settingsItem
=
_missionController
->
visualItems
()
->
value
<
MissionSettingsItem
*>
(
0
);
settingsItem
->
setMissionEndRTL
(
true
);
}
_missionController
->
insertLandItem
(
mapCenterCoord
,
-
1
);
_missionController
->
setCurrentPlanViewIndex
(
takeoffItem
->
sequenceNumber
(),
true
);
}
src/MissionManager/SurveyPlanCreator.cc
View file @
513d2cd8
...
...
@@ -23,15 +23,7 @@ void SurveyPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController
->
removeAll
();
VisualMissionItem
*
takeoffItem
=
_missionController
->
insertTakeoffItem
(
mapCenterCoord
,
-
1
);
takeoffItem
->
setWizardMode
(
true
);
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternSurveyName
,
mapCenterCoord
,
-
1
)
->
setWizardMode
(
true
);
if
(
_planMasterController
->
managerVehicle
()
->
fixedWing
())
{
FixedWingLandingComplexItem
*
landingItem
=
qobject_cast
<
FixedWingLandingComplexItem
*>
(
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternFWLandingName
,
mapCenterCoord
,
-
1
));
landingItem
->
setWizardMode
(
true
);
landingItem
->
setLoiterDragAngleOnly
(
true
);
}
else
{
MissionSettingsItem
*
settingsItem
=
_missionController
->
visualItems
()
->
value
<
MissionSettingsItem
*>
(
0
);
settingsItem
->
setMissionEndRTL
(
true
);
}
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternSurveyName
,
mapCenterCoord
,
-
1
);
_missionController
->
insertLandItem
(
mapCenterCoord
,
-
1
);
_missionController
->
setCurrentPlanViewIndex
(
takeoffItem
->
sequenceNumber
(),
true
);
}
src/PlanView/MissionSettingsEditor.qml
View file @
513d2cd8
...
...
@@ -107,28 +107,6 @@ Rectangle {
visible
:
_showCameraSection
&&
cameraSection
.
checked
}
SectionHeader
{
id
:
missionEndHeader
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
text
:
qsTr
(
"
Mission End
"
)
checked
:
true
}
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
missionEndHeader
.
checked
QGCCheckBox
{
text
:
qsTr
(
"
Return To Launch
"
)
checked
:
missionItem
.
missionEndRTL
onClicked
:
missionItem
.
missionEndRTL
=
checked
}
}
SectionHeader
{
id
:
vehicleInfoSectionHeader
anchors.left
:
parent
.
left
...
...
src/PlanView/PlanView.qml
View file @
513d2cd8
...
...
@@ -629,7 +629,8 @@ Item {
readonly
property
int
waypointButtonIndex
:
3
readonly
property
int
roiButtonIndex
:
4
readonly
property
int
patternButtonIndex
:
5
readonly
property
int
centerButtonIndex
:
6
readonly
property
int
landButtonIndex
:
6
readonly
property
int
centerButtonIndex
:
7
property
bool
_isRally
:
_editingLayer
==
_layerRallyPoints
...
...
@@ -677,6 +678,12 @@ Item {
buttonVisible
:
!
_isRally
,
dropPanelComponent
:
_singleComplexItem
?
undefined
:
patternDropPanel
},
{
name
:
_planMasterController
.
controllerVehicle
.
fixedWing
?
qsTr
(
"
Land
"
)
:
qsTr
(
"
Return
"
),
iconSource
:
"
/res/rtl.svg
"
,
buttonEnabled
:
_missionController
.
isInsertLandValid
,
buttonVisible
:
_editingLayer
==
_layerMission
},
{
name
:
qsTr
(
"
Center
"
),
iconSource
:
"
/qmlimages/MapCenter.svg
"
,
...
...
@@ -714,6 +721,9 @@ Item {
addComplexItem
(
_missionController
.
complexMissionItemNames
[
0
])
}
break
case
landButtonIndex
:
_missionController
.
insertLandItem
(
mapCenter
(),
_missionController
.
currentMissionIndex
,
true
/* makeCurrentItem */
)
break
}
}
}
...
...
@@ -1027,25 +1037,6 @@ Item {
}
}
}
Rectangle
{
width
:
parent
.
width
*
0.8
height
:
1
color
:
qgcPal
.
text
opacity
:
0.5
Layout.fillWidth
:
true
Layout.columnSpan
:
2
}
QGCButton
{
text
:
qsTr
(
"
Load KML/SHP...
"
)
Layout.fillWidth
:
true
enabled
:
!
_planMasterController
.
syncInProgress
onClicked
:
{
_planMasterController
.
loadShapeFromSelectedFile
()
dropPanel
.
hide
()
}
}
}
// Column
}
...
...
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