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
a95b2d32
Unverified
Commit
a95b2d32
authored
Aug 28, 2018
by
Don Gagne
Committed by
GitHub
Aug 28, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6836 from DonLakeFlyer/ResumeMission
Fix Resume Mission item count bug
parents
31fa444d
82cceb1a
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
48 additions
and
23 deletions
+48
-23
ChangeLog.md
ChangeLog.md
+6
-1
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+14
-12
MissionController.cc
src/MissionManager/MissionController.cc
+7
-3
MissionController.h
src/MissionManager/MissionController.h
+4
-0
QGCLoggingCategory.cc
src/QGCLoggingCategory.cc
+8
-7
QGCLoggingCategory.h
src/QGCLoggingCategory.h
+1
-0
QGCCorePlugin.cc
src/api/QGCCorePlugin.cc
+6
-0
QGCCorePlugin.h
src/api/QGCCorePlugin.h
+2
-0
No files found.
ChangeLog.md
View file @
a95b2d32
...
...
@@ -4,8 +4,13 @@ Note: This file only contains high level features or important fixes.
## 3.4
### 3.4.3 - Not yet released
*
Fix bug where Resume Mission would not display correctly in some cases. Issue #6835.
### 3.4.2
*
Fix bug where new mission items may end up with 0 altitude internally and sent to vehicle while UI shows correct altitude. Issue #6823.
### 3.4.1
*
Fix bug where new mission items may end up with 0 altitude internally and sent to vehicle while UI shows correct altitude.
*
Fix crash when Survery with terrain follow is moved quickly
*
Fix terrain follow climb/descent rate fields swapped in ui
src/FlightDisplay/GuidedActionsController.qml
View file @
a95b2d32
...
...
@@ -101,18 +101,19 @@ Item {
property
bool
showTakeoff
:
_guidedActionsEnabled
&&
_activeVehicle
.
takeoffVehicleSupported
&&
!
_vehicleFlying
property
bool
showLand
:
_guidedActionsEnabled
&&
_activeVehicle
.
guidedModeSupported
&&
_vehicleArmed
&&
!
_activeVehicle
.
fixedWing
&&
!
_vehicleInLandMode
property
bool
showStartMission
:
_guidedActionsEnabled
&&
_missionAvailable
&&
!
_missionActive
&&
!
_vehicleFlying
property
bool
showContinueMission
:
_guidedActionsEnabled
&&
_missionAvailable
&&
!
_missionActive
&&
_vehicleArmed
&&
_vehicleFlying
&&
(
_currentMissionIndex
<
missionController
.
visualItems
.
c
ount
-
1
)
property
bool
showContinueMission
:
_guidedActionsEnabled
&&
_missionAvailable
&&
!
_missionActive
&&
_vehicleArmed
&&
_vehicleFlying
&&
(
_currentMissionIndex
<
_missionItemC
ount
-
1
)
property
bool
showPause
:
_guidedActionsEnabled
&&
_vehicleArmed
&&
_activeVehicle
.
pauseVehicleSupported
&&
_vehicleFlying
&&
!
_vehiclePaused
property
bool
showChangeAlt
:
_guidedActionsEnabled
&&
_vehicleFlying
&&
_activeVehicle
.
guidedModeSupported
&&
_vehicleArmed
&&
!
_missionActive
property
bool
showOrbit
:
_guidedActionsEnabled
&&
!
_hideOrbit
&&
_vehicleFlying
&&
_activeVehicle
.
orbitModeSupported
&&
!
_missionActive
property
bool
showLandAbort
:
_guidedActionsEnabled
&&
_vehicleFlying
&&
_activeVehicle
.
fixedWing
&&
_vehicleLanding
property
bool
showGotoLocation
:
_guidedActionsEnabled
&&
_vehicleFlying
// Note: The '
missionController.visualItems.count - 3
' is a hack to not trigger resume mission when a mission ends with an RTL item
property
bool
showResumeMission
:
_activeVehicle
&&
!
_vehicleArmed
&&
_vehicleWasFlying
&&
_missionAvailable
&&
_resumeMissionIndex
>
0
&&
(
_resumeMissionIndex
<
missionController
.
visualItems
.
count
-
3
)
// Note: The '
_missionItemCount - 2
' is a hack to not trigger resume mission when a mission ends with an RTL item
property
bool
showResumeMission
:
_activeVehicle
&&
!
_vehicleArmed
&&
_vehicleWasFlying
&&
_missionAvailable
&&
_resumeMissionIndex
>
0
&&
(
_resumeMissionIndex
<
_missionItemCount
-
2
)
property
bool
guidedUIVisible
:
guidedActionConfirm
.
visible
||
guidedActionList
.
visible
property
var
_corePlugin
:
QGroundControl
.
corePlugin
property
bool
_guidedActionsEnabled
:
(
!
ScreenTools
.
isDebug
&&
QGroundControl
.
corePlugin
.
options
.
guidedActionsRequireRCRSSI
&&
_activeVehicle
)
?
_rcRSSIAvailable
:
_activeVehicle
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
string
_flightMode
:
_activeVehicle
?
_activeVehicle
.
flightMode
:
""
...
...
@@ -125,6 +126,7 @@ Item {
property
bool
_vehicleInMissionMode
:
false
property
bool
_vehicleInRTLMode
:
false
property
bool
_vehicleInLandMode
:
false
property
int
_missionItemCount
:
missionController
.
missionItemCount
property
int
_currentMissionIndex
:
missionController
.
currentMissionIndex
property
int
_resumeMissionIndex
:
missionController
.
resumeMissionIndex
property
bool
_hideEmergenyStop
:
!
QGroundControl
.
corePlugin
.
options
.
guidedBarShowEmergencyStop
...
...
@@ -132,15 +134,14 @@ Item {
property
bool
_vehicleWasFlying
:
false
property
bool
_rcRSSIAvailable
:
_activeVehicle
?
_activeVehicle
.
rcRSSI
>
0
&&
_activeVehicle
.
rcRSSI
<=
100
:
false
//Handy code for debugging state problems
property
bool
__debugGuidedStates
:
false
// You can turn on log output for GuidedActionsController by turning on GuidedActionsControllerLog category
property
bool
__guidedModeSupported
:
_activeVehicle
?
_activeVehicle
.
guidedModeSupported
:
false
property
bool
__pauseVehicleSupported
:
_activeVehicle
?
_activeVehicle
.
pauseVehicleSupported
:
false
property
bool
__flightMode
:
_flightMode
function
_outputState
()
{
if
(
_
_debugGuidedStates
)
{
console
.
log
(
qsTr
(
"
_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicle
InRTLMode(%5) pauseVehicleSupported(%6) _vehiclePaused(%7) _flightMode(%8)
"
).
arg
(
_activeVehicle
?
1
:
0
).
arg
(
_vehicleArmed
?
1
:
0
).
arg
(
__guidedModeSupported
?
1
:
0
).
arg
(
_vehicleFlying
?
1
:
0
).
arg
(
_vehicleInRTLMode
?
1
:
0
).
arg
(
__pauseVehicleSupported
?
1
:
0
).
arg
(
_vehiclePaused
?
1
:
0
).
arg
(
_flightMode
))
if
(
_
corePlugin
.
guidedActionsControllerLogging
()
)
{
console
.
log
(
qsTr
(
"
_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicle
WasFlying(%5) _vehicleInRTLMode(%6) pauseVehicleSupported(%7) _vehiclePaused(%8) _flightMode(%9) _missionItemCount(%10)
"
).
arg
(
_activeVehicle
?
1
:
0
).
arg
(
_vehicleArmed
?
1
:
0
).
arg
(
__guidedModeSupported
?
1
:
0
).
arg
(
_vehicleFlying
?
1
:
0
).
arg
(
_vehicleWasFlying
?
1
:
0
).
arg
(
_vehicleInRTLMode
?
1
:
0
).
arg
(
__pauseVehicleSupported
?
1
:
0
).
arg
(
_vehiclePaused
?
1
:
0
).
arg
(
_flightMode
).
arg
(
_missionItemCount
))
}
}
...
...
@@ -152,31 +153,32 @@ Item {
on__FlightModeChanged
:
_outputState
()
on__GuidedModeSupportedChanged
:
_outputState
()
on__PauseVehicleSupportedChanged
:
_outputState
()
on_MissionItemCountChanged
:
_outputState
()
on_CurrentMissionIndexChanged
:
{
if
(
_
_debugGuidedStates
)
{
if
(
_
corePlugin
.
guidedActionsControllerLogging
()
)
{
console
.
log
(
"
_currentMissionIndex
"
,
_currentMissionIndex
)
}
}
on_ResumeMissionIndexChanged
:
{
if
(
_
_debugGuidedStates
)
{
if
(
_
corePlugin
.
guidedActionsControllerLogging
()
)
{
console
.
log
(
"
_resumeMissionIndex
"
,
_resumeMissionIndex
)
}
}
onShowResumeMissionChanged
:
{
if
(
_
_debugGuidedStates
)
{
if
(
_
corePlugin
.
guidedActionsControllerLogging
()
)
{
console
.
log
(
"
showResumeMission
"
,
showResumeMission
)
}
_outputState
()
}
onShowStartMissionChanged
:
{
if
(
_
_debugGuidedStates
)
{
if
(
_
corePlugin
.
guidedActionsControllerLogging
()
)
{
console
.
log
(
"
showStartMission
"
,
showStartMission
)
}
_outputState
()
}
onShowContinueMissionChanged
:
{
if
(
_
_debugGuidedStates
)
{
if
(
_
corePlugin
.
guidedActionsControllerLogging
()
)
{
console
.
log
(
"
showContinueMission
"
,
showContinueMission
)
}
_outputState
()
...
...
src/MissionManager/MissionController.cc
View file @
a95b2d32
...
...
@@ -56,8 +56,9 @@ const int MissionController::_missionFileVersion = 2;
MissionController
::
MissionController
(
PlanMasterController
*
masterController
,
QObject
*
parent
)
:
PlanElementController
(
masterController
,
parent
)
,
_missionManager
(
_managerVehicle
->
missionManager
())
,
_visualItems
(
NULL
)
,
_settingsItem
(
NULL
)
,
_missionItemCount
(
0
)
,
_visualItems
(
nullptr
)
,
_settingsItem
(
nullptr
)
,
_firstItemsFromVehicle
(
false
)
,
_itemsRequested
(
false
)
,
_inRecalcSequence
(
false
)
...
...
@@ -68,7 +69,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
,
_appSettings
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
())
,
_progressPct
(
0
)
,
_currentPlanViewIndex
(
-
1
)
,
_currentPlanViewItem
(
NULL
)
,
_currentPlanViewItem
(
nullptr
)
{
_resetMissionFlightStatus
();
managerVehicleChanged
(
_managerVehicle
);
...
...
@@ -159,6 +160,9 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
const
QList
<
MissionItem
*>&
newMissionItems
=
_missionManager
->
missionItems
();
qCDebug
(
MissionControllerLog
)
<<
"loading from vehicle: count"
<<
newMissionItems
.
count
();
_missionItemCount
=
newMissionItems
.
count
();
emit
missionItemCountChanged
(
_missionItemCount
);
int
i
=
0
;
if
(
_controllerVehicle
->
firmwarePlugin
()
->
sendHomePositionToVehicle
()
&&
newMissionItems
.
count
()
!=
0
)
{
// First item is fake home position
...
...
src/MissionManager/MissionController.h
View file @
a95b2d32
...
...
@@ -73,6 +73,7 @@ public:
Q_PROPERTY
(
double
progressPct
READ
progressPct
NOTIFY
progressPctChanged
)
Q_PROPERTY
(
int
missionItemCount
READ
missionItemCount
NOTIFY
missionItemCountChanged
)
///< True mission item command count (only valid in Fly View)
Q_PROPERTY
(
int
currentMissionIndex
READ
currentMissionIndex
NOTIFY
currentMissionIndexChanged
)
Q_PROPERTY
(
int
resumeMissionIndex
READ
resumeMissionIndex
NOTIFY
resumeMissionIndexChanged
)
///< Returns the item index two which a mission should be resumed. -1 indicates resume mission not available.
...
...
@@ -170,6 +171,7 @@ public:
QString
corridorScanComplexItemName
(
void
)
const
{
return
_corridorScanMissionItemName
;
}
QString
structureScanComplexItemName
(
void
)
const
{
return
_structureScanMissionItemName
;
}
int
missionItemCount
(
void
)
const
{
return
_missionItemCount
;
}
int
currentMissionIndex
(
void
)
const
;
int
resumeMissionIndex
(
void
)
const
;
int
currentPlanViewIndex
(
void
)
const
;
...
...
@@ -208,6 +210,7 @@ signals:
void
currentMissionIndexChanged
(
int
currentMissionIndex
);
void
currentPlanViewIndexChanged
(
void
);
void
currentPlanViewItemChanged
(
void
);
void
missionItemCountChanged
(
int
missionItemCount
);
private
slots
:
void
_newMissionItemsAvailableFromVehicle
(
bool
removeAllRequested
);
...
...
@@ -260,6 +263,7 @@ private:
private:
MissionManager
*
_missionManager
;
int
_missionItemCount
;
QmlObjectListModel
*
_visualItems
;
MissionSettingsItem
*
_settingsItem
;
QmlObjectListModel
_waypointLines
;
...
...
src/QGCLoggingCategory.cc
View file @
a95b2d32
...
...
@@ -16,13 +16,14 @@
#include <QSettings>
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeLog
,
"FirmwareUpgradeLog"
)
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeVerboseLog
,
"FirmwareUpgradeVerboseLog"
)
QGC_LOGGING_CATEGORY
(
MissionCommandsLog
,
"MissionCommandsLog"
)
QGC_LOGGING_CATEGORY
(
MissionItemLog
,
"MissionItemLog"
)
QGC_LOGGING_CATEGORY
(
ParameterManagerLog
,
"ParameterManagerLog"
)
QGC_LOGGING_CATEGORY
(
GeotaggingLog
,
"GeotaggingLog"
)
QGC_LOGGING_CATEGORY
(
RTKGPSLog
,
"RTKGPSLog"
)
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeLog
,
"FirmwareUpgradeLog"
)
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeVerboseLog
,
"FirmwareUpgradeVerboseLog"
)
QGC_LOGGING_CATEGORY
(
MissionCommandsLog
,
"MissionCommandsLog"
)
QGC_LOGGING_CATEGORY
(
MissionItemLog
,
"MissionItemLog"
)
QGC_LOGGING_CATEGORY
(
ParameterManagerLog
,
"ParameterManagerLog"
)
QGC_LOGGING_CATEGORY
(
GeotaggingLog
,
"GeotaggingLog"
)
QGC_LOGGING_CATEGORY
(
RTKGPSLog
,
"RTKGPSLog"
)
QGC_LOGGING_CATEGORY
(
GuidedActionsControllerLog
,
"GuidedActionsControllerLog"
)
QGCLoggingCategoryRegister
*
_instance
=
NULL
;
const
char
*
QGCLoggingCategoryRegister
::
_filterRulesSettingsGroup
=
"LoggingFilters"
;
...
...
src/QGCLoggingCategory.h
View file @
a95b2d32
...
...
@@ -25,6 +25,7 @@ Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
Q_DECLARE_LOGGING_CATEGORY
(
ParameterManagerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
GeotaggingLog
)
Q_DECLARE_LOGGING_CATEGORY
(
RTKGPSLog
)
Q_DECLARE_LOGGING_CATEGORY
(
GuidedActionsControllerLog
)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
...
...
src/api/QGCCorePlugin.cc
View file @
a95b2d32
...
...
@@ -16,6 +16,7 @@
#include "AppMessages.h"
#include "QmlObjectListModel.h"
#include "VideoReceiver.h"
#include "QGCLoggingCategory.h"
#include <QtQml>
#include <QQmlEngine>
...
...
@@ -297,3 +298,8 @@ VideoReceiver* QGCCorePlugin::createVideoReceiver(QObject* parent)
{
return
new
VideoReceiver
(
parent
);
}
bool
QGCCorePlugin
::
guidedActionsControllerLogging
(
void
)
const
{
return
GuidedActionsControllerLog
().
isDebugEnabled
();
}
src/api/QGCCorePlugin.h
View file @
a95b2d32
...
...
@@ -51,6 +51,8 @@ public:
Q_PROPERTY
(
QString
brandImageOutdoor
READ
brandImageOutdoor
CONSTANT
)
Q_PROPERTY
(
QmlObjectListModel
*
customMapItems
READ
customMapItems
CONSTANT
)
Q_INVOKABLE
bool
guidedActionsControllerLogging
(
void
)
const
;
/// The list of settings under the Settings Menu
/// @return A list of QGCSettings
virtual
QVariantList
&
settingsPages
(
void
);
...
...
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